diff --git a/boards/aerotenna/ocpoc/ocpoc_adc/ocpoc_adc.cpp b/boards/aerotenna/ocpoc/ocpoc_adc/ocpoc_adc.cpp index 29a5ef92f2..6f2fc6a914 100644 --- a/boards/aerotenna/ocpoc/ocpoc_adc/ocpoc_adc.cpp +++ b/boards/aerotenna/ocpoc/ocpoc_adc/ocpoc_adc.cpp @@ -246,3 +246,8 @@ int ocpoc_adc_main(int argc, char *argv[]) return PX4_OK; } +// This is a replacement for the hardcoded 4096 +uint32_t px4_arch_adc_dn_fullcount(void) +{ + return 1 << 12; // 12 bit ADC +} diff --git a/platforms/common/include/px4_platform_common/board_common.h b/platforms/common/include/px4_platform_common/board_common.h index 3cfd018c70..5058a7ad19 100644 --- a/platforms/common/include/px4_platform_common/board_common.h +++ b/platforms/common/include/px4_platform_common/board_common.h @@ -373,6 +373,8 @@ typedef enum PX4_SOC_ARCH_ID_t { PX4_SOC_ARCH_ID_KINETISK66 = 0x0003, PX4_SOC_ARCH_ID_SAMV7 = 0x0004, + PX4_SOC_ARCH_ID_STM32H7 = 0x0006, + PX4_SOC_ARCH_ID_EAGLE = 0x1001, PX4_SOC_ARCH_ID_QURT = 0x1002, PX4_SOC_ARCH_ID_OCPOC = 0x1003, diff --git a/platforms/nuttx/NuttX/CMakeLists.txt b/platforms/nuttx/NuttX/CMakeLists.txt index 0854992b13..2f9b6a8c93 100644 --- a/platforms/nuttx/NuttX/CMakeLists.txt +++ b/platforms/nuttx/NuttX/CMakeLists.txt @@ -317,7 +317,7 @@ add_custom_target(nuttx_builtin_list_target # libapps.a add_custom_command(OUTPUT ${APPS_DIR}/libapps.a ${APPS_DIR}/platform/.built COMMAND find ${APPS_DIR} -name \*.o -delete - COMMAND make ${nuttx_build_options} --no-print-directory -C ../apps TOPDIR="${NUTTX_DIR}" libapps.a > nuttx_apps.log + COMMAND make ${nuttx_build_options} --no-print-directory TOPDIR="${NUTTX_DIR}" ../apps/libapps.a > nuttx_apps.log DEPENDS nuttx_builtin_list_target ${nuttx_builtin_list} nuttx_context diff --git a/platforms/nuttx/cmake/init.cmake b/platforms/nuttx/cmake/init.cmake index 3d6631ebe8..4f3bbab5d4 100644 --- a/platforms/nuttx/cmake/init.cmake +++ b/platforms/nuttx/cmake/init.cmake @@ -92,6 +92,11 @@ execute_process(COMMAND ${cp_cmd} ${cp_opts} ${CP_SRC} ${CP_DST} WORKING_DIRECTO set(NUTTX_DEFCONFIG ${NUTTX_CONFIG_DIR}/${NUTTX_CONFIG}/defconfig CACHE FILEPATH "path to defconfig" FORCE) +############################################################################### +# Create a temporary Toplevel Make.defs for the oldconfig step +############################################################################### +configure_file(${NUTTX_SRC_DIR}/Make.defs.in ${NUTTX_DIR}/Make.defs) + # If the board provides a Kconfig Use it or create an empty one if(EXISTS ${NUTTX_CONFIG_DIR}/Kconfig) execute_process(COMMAND ${CMAKE_COMMAND} -E copy_if_different ${NUTTX_CONFIG_DIR}/Kconfig ${NUTTX_DIR}/boards/dummy/Kconfig) @@ -120,7 +125,17 @@ if (NOT config_expanded) WORKING_DIRECTORY ${NUTTX_DIR} OUTPUT_FILE nuttx_olddefconfig.log ERROR_FILE nuttx_olddefconfig.log + RESULT_VARIABLE ret ) + if(NOT ret EQUAL "0") + # Show the log here as it will be deleted due to the incomplete configure step + file(READ ${NUTTX_DIR}/nuttx_olddefconfig.log DEFCONFIG_LOG) + message( STATUS "${DEFCONFIG_LOG}") + message( FATAL_ERROR "NuttX olddefconfig target failed. \ +Possible cause: the board (${NUTTX_CONFIG_DIR}/${NUTTX_CONFIG}) has the wrong directory structure (i.e. missing files).") + endif() + # remove Toplevel Make.defs + file(REMOVE ${NUTTX_DIR}/Make.defs) endif() ############################################################################### diff --git a/platforms/nuttx/cmake/px4_impl_os.cmake b/platforms/nuttx/cmake/px4_impl_os.cmake index 0f237d2e7d..727f540a89 100644 --- a/platforms/nuttx/cmake/px4_impl_os.cmake +++ b/platforms/nuttx/cmake/px4_impl_os.cmake @@ -107,6 +107,9 @@ function(px4_os_determine_build_chip) elseif(CONFIG_ARCH_CHIP_STM32F7) set(CHIP_MANUFACTURER "stm") set(CHIP "stm32f7") + elseif(CONFIG_ARCH_CHIP_STM32H7) + set(CHIP_MANUFACTURER "stm") + set(CHIP "stm32h7") elseif(CONFIG_ARCH_CHIP_MK66FN2M0VMD18) set(CHIP_MANUFACTURER "nxp") set(CHIP "k66") diff --git a/platforms/nuttx/src/px4/common/board_crashdump.c b/platforms/nuttx/src/px4/common/board_crashdump.c index ef0dc7244f..2d00c90bed 100644 --- a/platforms/nuttx/src/px4/common/board_crashdump.c +++ b/platforms/nuttx/src/px4/common/board_crashdump.c @@ -1,3 +1,43 @@ +/**************************************************************************** + * + * Copyright (C) 2017-2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_crashdump.c + * + * Provides common board logic for crashdump callout + * and hardfault log support + */ + #ifdef CONFIG_BOARD_CRASHDUMP #include @@ -18,6 +58,10 @@ # define HAS_BBSRAM CONFIG_STM32F7_BBSRAM # define BBSRAM_FILE_COUNT CONFIG_STM32F7_BBSRAM_FILES # define SAVE_CRASHDUMP CONFIG_STM32F7_SAVE_CRASHDUMP +#elif defined(CONFIG_STM32H7_BBSRAM) && defined(CONFIG_STM32H7_SAVE_CRASHDUMP) +# define HAS_BBSRAM CONFIG_STM32H7_BBSRAM +# define BBSRAM_FILE_COUNT CONFIG_STM32H7_BBSRAM_FILES +# define SAVE_CRASHDUMP CONFIG_STM32H7_SAVE_CRASHDUMP #elif defined(CONFIG_STM32_BBSRAM) && defined(CONFIG_STM32_SAVE_CRASHDUMP) # define HAS_BBSRAM CONFIG_STM32_BBSRAM # define BBSRAM_FILE_COUNT CONFIG_STM32_BBSRAM_FILES diff --git a/platforms/nuttx/src/px4/stm/stm32_common/adc/adc.cpp b/platforms/nuttx/src/px4/stm/stm32_common/adc/adc.cpp index 6661c27c1c..7a308e6767 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/adc/adc.cpp +++ b/platforms/nuttx/src/px4/stm/stm32_common/adc/adc.cpp @@ -32,6 +32,7 @@ ****************************************************************************/ #include +#include #include #include #include @@ -190,7 +191,7 @@ void px4_arch_adc_uninit(uint32_t base_address) // nothing to do } -uint16_t px4_arch_adc_sample(uint32_t base_address, unsigned channel) +uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel) { irqstate_t flags = px4_enter_critical_section(); @@ -211,12 +212,12 @@ uint16_t px4_arch_adc_sample(uint32_t base_address, unsigned channel) /* don't wait for more than 50us, since that means something broke - should reset here if we see this */ if ((hrt_absolute_time() - now) > 50) { px4_leave_critical_section(flags); - return 0xffff; + return UINT32_MAX; } } /* read the result and clear EOC */ - uint16_t result = rDR(base_address); + uint32_t result = rDR(base_address); px4_leave_critical_section(flags); @@ -228,3 +229,7 @@ uint32_t px4_arch_adc_temp_sensor_mask() return 1 << 16; } +uint32_t px4_arch_adc_dn_fullcount(void) +{ + return 1 << 12; // 12 bit ADC +} diff --git a/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp index cdac39156b..cf07376ede 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp +++ b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp @@ -145,8 +145,32 @@ # if defined(CONFIG_STM32_TIM14) # error Must not set CONFIG_STM32_TIM14 when TONE_ALARM_TIMER is 14 # endif +#elif TONE_ALARM_TIMER == 15 +# define TONE_ALARM_BASE STM32_TIM15_BASE +# define TONE_ALARM_CLOCK STM32_APB2_TIM15_CLKIN +# define TONE_ALARM_CLOCK_ENABLE RCC_APB2ENR_TIM15EN +# define TONE_ALARM_CLOCK_POWER_REG STM32_RCC_APB2ENR +# if defined(CONFIG_STM32_TIM15) +# error Must not set CONFIG_STM32_TIM15 when TONE_ALARM_TIMER is 15 +# endif +#elif TONE_ALARM_TIMER == 16 +# define TONE_ALARM_BASE STM32_TIM16_BASE +# define TONE_ALARM_CLOCK STM32_APB2_TIM16_CLKIN +# define TONE_ALARM_CLOCK_ENABLE RCC_APB2ENR_TIM16EN +# define TONE_ALARM_CLOCK_POWER_REG STM32_RCC_APB2ENR +# if defined(CONFIG_STM32_TIM16) +# error Must not set CONFIG_STM32_TIM16 when TONE_ALARM_TIMER is 16 +# endif +#elif TONE_ALARM_TIMER == 17 +# define TONE_ALARM_BASE STM32_TIM17_BASE +# define TONE_ALARM_CLOCK STM32_APB2_TIM17_CLKIN +# define TONE_ALARM_CLOCK_ENABLE RCC_APB2ENR_TIM17EN +# define TONE_ALARM_CLOCK_POWER_REG STM32_RCC_APB2ENR +# if defined(CONFIG_STM32_TIM17) +# error Must not set CONFIG_STM32_TIM16 when TONE_ALARM_TIMER is 17 +# endif #else -# error Must set TONE_ALARM_TIMER to one of the timers between 1 and 14 (inclusive) to use this driver. +# error Must set TONE_ALARM_TIMER to one of the timers between 1 and 17 (inclusive) to use this driver. #endif // TONE_ALARM_TIMER #if TONE_ALARM_CHANNEL == 1 @@ -199,6 +223,9 @@ # define rSR REG(STM32_ATIM_SR_OFFSET) #else # define rARR REG(STM32_GTIM_ARR_OFFSET) +#if TONE_ALARM_TIMER >= 15 && TONE_ALARM_TIMER <= 17 // Note: If using TIM15 - TIM17 it has a BDTR +# define rBDTR REG(STM32_ATIM_BDTR_OFFSET) +#endif # define rCCER REG(STM32_GTIM_CCER_OFFSET) # define rCCMR1 REG(STM32_GTIM_CCMR1_OFFSET) # define rCCMR2 REG(STM32_GTIM_CCMR2_OFFSET) diff --git a/platforms/nuttx/src/px4/stm/stm32_common/version/board_mcu_version.c b/platforms/nuttx/src/px4/stm/stm32_common/version/board_mcu_version.c index cf44434673..087f0153a7 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/version/board_mcu_version.c +++ b/platforms/nuttx/src/px4/stm/stm32_common/version/board_mcu_version.c @@ -47,7 +47,9 @@ enum MCU_REV { MCU_REV_STM32F4_REV_Z = 0x1001, MCU_REV_STM32F4_REV_Y = 0x1003, MCU_REV_STM32F4_REV_1 = 0x1007, - MCU_REV_STM32F4_REV_3 = 0x2001 + MCU_REV_STM32F4_REV_3 = 0x2001, + MCU_REV_STM32F7_REV_X = MCU_REV_STM32F4_REV_3, + MCU_REV_STM32F7_REV_V = 0x2003 }; /* Define any issues with the Silicon as lines separated by \n @@ -60,6 +62,7 @@ enum MCU_REV { # define REVID_MASK 0xFFFF0000 # define DEVID_MASK 0xFFF +# define STM32H74xx_75xx 0x450 # define STM32F74xxx_75xxx 0x449 # define STM32F76xxx_77xxx 0x451 # define STM32F40x_41x 0x413 @@ -81,6 +84,10 @@ int board_mcu_version(char *rev, const char **revstr, const char **errata) switch (chip_version) { + case STM32H74xx_75xx: + *revstr = "STM32H74xxx"; + break; + case STM32F74xxx_75xxx: *revstr = "STM32F74xxx"; break; @@ -139,7 +146,12 @@ int board_mcu_version(char *rev, const char **revstr, const char **errata) break; case MCU_REV_STM32F4_REV_3: - *rev = '3'; + *rev = chip_version == STM32H74xx_75xx ? 'X' : '3' ; + chip_errata = NULL; + break; + + case MCU_REV_STM32F7_REV_V: + *rev = 'V'; chip_errata = NULL; break; diff --git a/platforms/nuttx/src/px4/stm/stm32h7/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32h7/CMakeLists.txt new file mode 100644 index 0000000000..d813819859 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/CMakeLists.txt @@ -0,0 +1,46 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(adc) +add_subdirectory(../stm32_common/board_critmon board_critmon) +add_subdirectory(../stm32_common/board_hw_info board_hw_info) +add_subdirectory(../stm32_common/board_reset board_reset) +add_subdirectory(../stm32_common/dshot dshot) +add_subdirectory(../stm32_common/hrt hrt) +add_subdirectory(../stm32_common/io_pins io_pins) +add_subdirectory(../stm32_common/tone_alarm tone_alarm) +add_subdirectory(../stm32_common/version version) + +add_subdirectory(px4io_serial) + diff --git a/platforms/nuttx/src/px4/stm/stm32h7/adc/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32h7/adc/CMakeLists.txt new file mode 100644 index 0000000000..d2487d05bf --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/adc/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2015-2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(arch_adc + adc.cpp +) diff --git a/platforms/nuttx/src/px4/stm/stm32h7/adc/adc.cpp b/platforms/nuttx/src/px4/stm/stm32h7/adc/adc.cpp new file mode 100644 index 0000000000..9fc045129e --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/adc/adc.cpp @@ -0,0 +1,315 @@ +/**************************************************************************** + * + * Copyright (C) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include +#include +#include + +#include +#include + + +/* + * Register accessors. + * For now, no reason not to just use ADC1. + */ +#define REG(base, _reg) (*(volatile uint32_t *)((base) + (_reg))) + +#define rCR(base) REG((base), STM32_ADC_CR_OFFSET) +#define rISR(base) REG((base), STM32_ADC_ISR_OFFSET) +#define rSMPR1(base) REG((base), STM32_ADC_SMPR1_OFFSET) +#define rSMPR2(base) REG((base), STM32_ADC_SMPR2_OFFSET) +#define rPCSEL(base) REG((base), STM32_ADC_PCSEL_OFFSET) +#define rCFG(base) REG((base), STM32_ADC_CFGR_OFFSET) +#define rCFG2(base) REG((base), STM32_ADC_CFGR2_OFFSET) +#define rCCR(base) REG((base), STM32_ADC_CCR_OFFSET) +#define rSQR1(base) REG((base), STM32_ADC_SQR1_OFFSET) +#define rSQR2(base) REG((base), STM32_ADC_SQR2_OFFSET) +#define rSQR3(base) REG((base), STM32_ADC_SQR3_OFFSET) +#define rSQR4(base) REG((base), STM32_ADC_SQR4_OFFSET) +#define rDR(base) REG((base), STM32_ADC_DR_OFFSET) + +#define ADC_SMPR_DEFAULT ADC_SMPR_64p5 // 64.5 +7.5 * 24 Mhz is 3 uS +#define ADC_SMPR1_DEFAULT ((ADC_SMPR_DEFAULT << ADC_SMPR1_SMP0_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP1_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP2_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP3_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP4_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP5_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP6_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP7_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP8_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR1_SMP9_SHIFT)) +#define ADC_SMPR2_DEFAULT ((ADC_SMPR_DEFAULT << ADC_SMPR2_SMP10_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP11_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP12_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP13_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP14_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP15_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP16_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP17_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP18_SHIFT) | \ + (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP19_SHIFT)) + + +/* Assuming VDC 2.4 - 3.6 */ + +#define ADC_MAX_FADC 36000000 + +#if STM32_PLL2P_FREQUENCY <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_NOT_DIV +#elif STM32_PLL2P_FREQUENCY/2 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV2 +#elif STM32_PLL2P_FREQUENCY/4 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV4 +#elif STM32_PLL2P_FREQUENCY/6 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV6 +#elif STM32_PLL2P_FREQUENCY/8 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV8 +#elif STM32_PLL2P_FREQUENCY/10 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV10 +#elif STM32_PLL2P_FREQUENCY/12 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV12 +#elif STM32_PLL2P_FREQUENCY/16 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV16 +#elif STM32_PLL2P_FREQUENCY/32 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV32 +#elif STM32_PLL2P_FREQUENCY/64 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV64 +#elif STM32_PLL2P_FREQUENCY/128 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV128 +#elif STM32_PLL2P_FREQUENCY/256 <= ADC_MAX_FADC +# define ADC_CCR_PRESC_DIV ADC_CCR_PRESC_DIV256 +#else +# error "ADC STM32_PLL2P_FREQUENCY too high - no divisor found " +#endif + + +int px4_arch_adc_init(uint32_t base_address) +{ + /* Perform ADC init once per ADC */ + + static uint32_t once[SYSTEM_ADC_COUNT] {}; + + uint32_t *free = nullptr; + + for (uint32_t i = 0; i < SYSTEM_ADC_COUNT; i++) { + if (once[i] == base_address) { + + /* This one was done already */ + + return OK; + } + + /* Use first free slot */ + + if (free == nullptr && once[i] == 0) { + free = &once[i]; + } + } + + if (free == nullptr) { + + /* ADC misconfigured SYSTEM_ADC_COUNT too small */; + + PANIC(); + } + + *free = base_address; + + /* do calibration if supported */ + + rCR(base_address) = ADC_CR_ADVREGEN | ADC_CR_BOOST; + + /* Wait for voltage regulator to power up */ + + up_udelay(20); + + /* enable the temperature sensor, VREFINT channel and VBAT */ + + rCCR(base_address) = (ADC_CCR_VREFEN | ADC_CCR_VSENSEEN | ADC_CCR_VBATEN | + ADC_CCR_CKMODE_ASYCH | ADC_CCR_PRESC_DIV); + + /* Enable ADC calibration. ADCALDIF == 0 so this is only for + * single-ended conversions, not for differential ones. + * Do Liner Cal first + */ + + rCR(base_address) |= ADC_CR_ADCALLIN; + rCR(base_address) |= ADC_CR_ADCAL; + + /* Wait for calibration to complete */ + + hrt_abstime now = hrt_absolute_time(); + + while ((rCR(base_address) & ADC_CR_ADCAL)) { + + /* don't wait for more than 7000us, since that means something broke + * should reset here if we see this */ + if ((hrt_absolute_time() - now) > 7000) { + return -1; + } + } + + rCR(base_address) &= ~ADC_CR_ADCALLIN; + + rCR(base_address) |= ADC_CR_ADCAL; + + /* Wait for calibration to complete */ + + now = hrt_absolute_time(); + + while ((rCR(base_address) & ADC_CR_ADCAL)) { + + /* don't wait for more than 500us, since that means something broke + * should reset here if we see this */ + if ((hrt_absolute_time() - now) > 500) { + return -2; + } + } + + + /* Enable ADC + * Note: ADEN bit cannot be set during ADCAL=1 and 4 ADC clock cycle + * after the ADCAL bit is cleared by hardware. If we are using SYSCLK + * as ADC clock source, this is the same as time taken to execute 4 + * ARM instructions. + */ + + rCR(base_address) |= ADC_CR_ADEN; + + now = hrt_absolute_time(); + + /* Wait for hardware to be ready for conversions */ + + while ((rISR(base_address) & ADC_INT_ADRDY) == 0) { + + /* don't wait for more than 500us, since that means something broke + * should reset here if we see this */ + if ((hrt_absolute_time() - now) > 500) { + return -3; + } + } + + + /* arbitrarily configure all channels for 810.5 cycle sample time */ + + rSMPR1(base_address) = ADC_SMPR1_DEFAULT; + rSMPR2(base_address) = ADC_SMPR2_DEFAULT; + + + /* Set CFGR configuration + * Set the resolution of the conversion. + * Disable external trigger for regular channels + */ + + rCFG(base_address) = (ADC_CFGR_RES_16BIT | ADC_CFGR_EXTEN_NONE); + + /* Set CFGR2 configuration to align right no oversample */ + + rCFG2(base_address) = 0; + + /* configure for a single-channel sequence */ + + rSQR1(base_address) = 0; + rSQR2(base_address) = 0; + rSQR3(base_address) = 0; + rSQR4(base_address) = 0; + + /* kick off a sample and wait for it to complete */ + now = hrt_absolute_time(); + rCR(base_address) |= ADC_CR_ADSTART; + + while (!(rISR(base_address) & ADC_INT_EOC)) { + + /* don't wait for more than 50us, since that means something broke - should reset here if we see this */ + if ((hrt_absolute_time() - now) > 50) { + return -4; + } + } + + return OK; +} + +void px4_arch_adc_uninit(uint32_t base_address) +{ + // nothing to do +} + +uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel) +{ + irqstate_t flags = px4_enter_critical_section(); + + /* clear any previous EOC */ + + if (rISR(base_address) & ADC_INT_EOC) { + rISR(base_address) &= ~ADC_INT_EOC; + } + + /* run a single conversion right now - should take about 810.5 cycles (34 microseconds) max */ + + rPCSEL(base_address) |= 1 << channel; + rSQR1(base_address) = channel << ADC_SQR1_SQ_OFFSET; + rCR(base_address) |= ADC_CR_ADSTART; + + /* wait for the conversion to complete */ + const hrt_abstime now = hrt_absolute_time(); + + while (!(rISR(base_address) & ADC_INT_EOC)) { + + /* don't wait for more than 50us, since that means something broke - should reset here if we see this */ + if ((hrt_absolute_time() - now) > 50) { + px4_leave_critical_section(flags); + return UINT32_MAX; + } + } + + /* read the result and clear EOC */ + uint32_t result = rDR(base_address); + + px4_leave_critical_section(flags); + + return result; +} + +uint32_t px4_arch_adc_temp_sensor_mask() +{ + return 1 << 16; +} + +uint32_t px4_arch_adc_dn_fullcount(void) +{ + return 1 << 16; // 16 bit ADC +} diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/adc.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/adc.h new file mode 100644 index 0000000000..3ccc32b0f8 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/adc.h @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + +#include + +#include + + +/* Historically PX4 used one ADC1 With FMUvnX this has changes. + * These defines maintain compatibility while allowing the + * new boards to override the ADC used from HW VER/REV and + * the system one. + * + * Depending on HW configuration (VER/REV POP options) hardware detection + * may or may NOT initialize a given ADC. SYSTEM_ADC_COUNT is used to size the + * singleton array to ensure this is only done once per ADC. + */ + +#if !defined(HW_REV_VER_ADC_BASE) +# define HW_REV_VER_ADC_BASE STM32_ADC1_BASE +#endif + +#if !defined(SYSTEM_ADC_BASE) +# define SYSTEM_ADC_BASE STM32_ADC1_BASE +#endif + +#include + diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer.h new file mode 100644 index 0000000000..2960835d2e --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer.h @@ -0,0 +1,37 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/io_timer.h" + diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h new file mode 100644 index 0000000000..6e1a338cf2 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/micro_hal.h" + +__BEGIN_DECLS + +#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_STM32H7 +#include +#include +#include //include up_systemreset() which is included on stm32.h +#include +#define PX4_BBSRAM_SIZE STM32H7_BBSRAM_SIZE +#define PX4_BBSRAM_GETDESC_IOCTL STM32H7_BBSRAM_GETDESC_IOCTL +#define PX4_FLASH_BASE 0x08000000 +#define PX4_NUMBER_I2C_BUSES STM32H7_NI2C + +int stm32h7_flash_lock(size_t addr); +int stm32h7_flash_unlock(size_t addr); +int stm32h7_flash_writeprotect(size_t block, bool enabled); +#define stm32_flash_lock() stm32h7_flash_lock(PX4_FLASH_BASE) + +__END_DECLS + diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/px4io_serial.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/px4io_serial.h new file mode 100644 index 0000000000..0e78048670 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/px4io_serial.h @@ -0,0 +1,38 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#define PX4IO_SERIAL_BUF_ALIGN ARMV7M_DCACHE_LINESIZE +#include "../../../stm32_common/include/px4_arch/px4io_serial.h" + diff --git a/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/CMakeLists.txt new file mode 100644 index 0000000000..df450593b1 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2015-2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(arch_px4io_serial + px4io_serial.cpp +) diff --git a/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/px4io_serial.cpp b/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/px4io_serial.cpp new file mode 100644 index 0000000000..1908b18913 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/px4io_serial.cpp @@ -0,0 +1,548 @@ +/**************************************************************************** + * + * Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4io_serial.cpp + * + * Serial interface for PX4IO on STM32F7 + */ + +#include + +#include "stm32_uart.h" +#include + +/* serial register accessors */ +#define REG(_x) (*(volatile uint32_t *)(PX4IO_SERIAL_BASE + (_x))) +#define rISR REG(STM32_USART_ISR_OFFSET) +#define rISR_ERR_FLAGS_MASK (0x1f) +#define rICR REG(STM32_USART_ICR_OFFSET) +#define rRDR REG(STM32_USART_RDR_OFFSET) +#define rTDR REG(STM32_USART_TDR_OFFSET) +#define rBRR REG(STM32_USART_BRR_OFFSET) +#define rCR1 REG(STM32_USART_CR1_OFFSET) +#define rCR2 REG(STM32_USART_CR2_OFFSET) +#define rCR3 REG(STM32_USART_CR3_OFFSET) +#define rGTPR REG(STM32_USART_GTPR_OFFSET) + +/* + * + * #define USART_CR1_FIFOEN (1 << 29) Bit 29: FIFO mode enable + * #define USART_CR1_TXFEIE (1 << 30) Bit 30: TXFIFO empty interrupt enable + * #define USART_CR1_RXFFIE (1 << 31) Bit 31: RXFIFO Full interrupt enable + * + * + * #define USART_CR2_SLVEN (1 << 0) Bit 0: Synchronous Slave mode enable + * #define USART_CR2_DISNSS (1 << 3) Bit 3: Ignore NSS pin input + * #define USART_CR3_RXFTCFG_SHIFT (25) Bit 25-27: Receive FIFO threshold configuration + * #define USART_CR3_RXFTCFG_MASK (7 << USART_CR3_RXFTCFG_SHIFT) + * # define USART_CR3_RXFTCFG(n) ((uint32_t)(n) << USART_CR3_RXFTCFG_SHIFT) + * # define USART_CR3_RXFTCFG_12PCT (0 << USART_CR3_RXFTCFG_SHIFT) RXFIFO 1/8 full + * # define USART_CR3_RXFTCFG_25PCT (1 << USART_CR3_RXFTCFG_SHIFT) RXFIFO 1/4 full + *# define USART_CR3_RXFTCFG_50PCT (2 << USART_CR3_RXFTCFG_SHIFT) RXFIFO 1/2 full + *# define USART_CR3_RXFTCFG_75PCT (3 << USART_CR3_RXFTCFG_SHIFT) RXFIFO 3/4 full + * # define USART_CR3_RXFTCFG_88PCT (4 << USART_CR3_RXFTCFG_SHIFT) RXFIFO 7/8 full + * # define USART_CR3_RXFTCFG_FULL (5 << USART_CR3_RXFTCFG_SHIFT) RXIFO full + * #define USART_CR3_RXFTIE (1 << 28) Bit 28: RXFIFO threshold interrupt enable + *#define USART_CR3_TXFTCFG_SHIFT (29) Bits 29-31: TXFIFO threshold configuration + * #define USART_CR3_TXFTCFG_MASK (7 << USART_CR3_TXFTCFG_SHIFT) + * # define USART_CR3_TXFTCFG(n) ((uint32_t)(n) << USART_CR3_TXFTCFG_SHIFT) + * # define USART_CR3_TXFTCFG_12PCT (0 << USART_CR3_TXFTCFG_SHIFT) TXFIFO 1/8 full + *# define USART_CR3_TXFTCFG_24PCT (1 << USART_CR3_TXFTCFG_SHIFT) TXFIFO 1/4 full + *# define USART_CR3_TXFTCFG_50PCT (2 << USART_CR3_TXFTCFG_SHIFT) TXFIFO 1/2 full + * # define USART_CR3_TXFTCFG_75PCT (3 << USART_CR3_TXFTCFG_SHIFT) TXFIFO 3/4 full + * # define USART_CR3_TXFTCFG_88PCT (4 << USART_CR3_TXFTCFG_SHIFT) TXFIFO 7/8 full + * # define USART_CR3_TXFTCFG_EMPY (5 << USART_CR3_TXFTCFG_SHIFT) TXFIFO empty +#define USART_ISR_RWU (1 << 19) Bit 19: Receiver wakeup from Mute mode +#define USART_ISR_WUF (1 << 20) Bit 20: Wakeup from low-power mode flag +#define USART_ISR_TEACK (1 << 21) Bit 21: Transmit enable acknowledge flag +#define USART_ISR_REACK (1 << 22) Bit 22: Receive enable acknowledge flag +#define USART_ISR_TXFE (1 << 23) Bit 23: TXFIFO Empty +#define USART_ISR_RXFF (1 << 24) Bit 24: RXFIFO Full * +#define USART_ISR_TCBGT (1 << 25) Bit 25: Transmission complete before guard time flag +#define USART_ISR_RXFT (1 << 26) Bit 26: RXFIFO threshold flag uint8_t +#define USART_ISR_TXFT (1 << 27) Bit 27: TXFIFO threshold flag +*/ + +#define DMA_BUFFER_MASK (ARMV7M_DCACHE_LINESIZE - 1) +#define DMA_ALIGN_UP(n) (((n) + DMA_BUFFER_MASK) & ~DMA_BUFFER_MASK) + +uint8_t ArchPX4IOSerial::_io_buffer_storage[DMA_ALIGN_UP(sizeof(IOPacket))]; + +ArchPX4IOSerial::ArchPX4IOSerial() : + _tx_dma(nullptr), + _rx_dma(nullptr), + _current_packet(nullptr), + _rx_dma_status(_dma_status_inactive), + _completion_semaphore(SEM_INITIALIZER(0)), +#if 0 + _pc_dmasetup(perf_alloc(PC_ELAPSED, "io_dmasetup ")), + _pc_dmaerrs(perf_alloc(PC_COUNT, "io_dmaerrs ")) +#else + _pc_dmasetup(nullptr), + _pc_dmaerrs(nullptr) +#endif +{ +} + +ArchPX4IOSerial::~ArchPX4IOSerial() +{ + if (_tx_dma != nullptr) { + stm32_dmastop(_tx_dma); + stm32_dmafree(_tx_dma); + } + + if (_rx_dma != nullptr) { + stm32_dmastop(_rx_dma); + stm32_dmafree(_rx_dma); + } + + /* reset the UART */ + rCR1 = 0; + rCR2 = 0; + rCR3 = 0; + + /* detach our interrupt handler */ + up_disable_irq(PX4IO_SERIAL_VECTOR); + irq_detach(PX4IO_SERIAL_VECTOR); + + /* restore the GPIOs */ + px4_arch_unconfiggpio(PX4IO_SERIAL_TX_GPIO); + px4_arch_unconfiggpio(PX4IO_SERIAL_RX_GPIO); + + /* Disable APB clock for the USART peripheral */ + modifyreg32(PX4IO_SERIAL_RCC_REG, PX4IO_SERIAL_RCC_EN, 0); + + /* and kill our semaphores */ + px4_sem_destroy(&_completion_semaphore); + + perf_free(_pc_dmasetup); + perf_free(_pc_dmaerrs); +} + +int +ArchPX4IOSerial::init() +{ + /* initialize base implementation */ + int r = PX4IO_serial::init((IOPacket *)&_io_buffer_storage[0]); + + if (r != 0) { + return r; + } + + /* allocate DMA */ + _tx_dma = stm32_dmachannel(PX4IO_SERIAL_TX_DMAMAP); + _rx_dma = stm32_dmachannel(PX4IO_SERIAL_RX_DMAMAP); + + if ((_tx_dma == nullptr) || (_rx_dma == nullptr)) { + return -1; + } + + /* Enable the APB clock for the USART peripheral */ + modifyreg32(PX4IO_SERIAL_RCC_REG, 0, PX4IO_SERIAL_RCC_EN); + + /* configure pins for serial use */ + px4_arch_configgpio(PX4IO_SERIAL_TX_GPIO); + px4_arch_configgpio(PX4IO_SERIAL_RX_GPIO); + + /* reset & configure the UART */ + rCR1 = 0; + rCR2 = 0; + rCR3 = 0; + + /* clear data that may be in the RDR and clear overrun error: */ + if (rISR & USART_ISR_RXNE) { + (void)rRDR; + } + + rICR = rISR & rISR_ERR_FLAGS_MASK; /* clear the flags */ + + /* configure line speed */ + uint32_t usartdiv32 = (PX4IO_SERIAL_CLOCK + (PX4IO_SERIAL_BITRATE) / 2) / (PX4IO_SERIAL_BITRATE); + rBRR = usartdiv32; + + /* attach serial interrupt handler */ + irq_attach(PX4IO_SERIAL_VECTOR, _interrupt, this); + up_enable_irq(PX4IO_SERIAL_VECTOR); + + /* enable UART in DMA mode, enable error and line idle interrupts */ + rCR3 = USART_CR3_EIE; + /* TODO: maybe use DDRE */ + + rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE; + /* TODO: maybe we need to adhere to the procedure as described in the reference manual page 1251 (34.5.2) */ + + /* create semaphores */ + px4_sem_init(&_completion_semaphore, 0, 0); + + /* _completion_semaphore use case is a signal */ + + px4_sem_setprotocol(&_completion_semaphore, SEM_PRIO_NONE); + + /* XXX this could try talking to IO */ + + return 0; +} + +int +ArchPX4IOSerial::ioctl(unsigned operation, unsigned &arg) +{ + switch (operation) { + + case 1: /* XXX magic number - test operation */ + switch (arg) { + case 0: + syslog(LOG_INFO, "test 0\n"); + + /* kill DMA, this is a PIO test */ + stm32_dmastop(_tx_dma); + stm32_dmastop(_rx_dma); + rCR3 &= ~(USART_CR3_DMAR | USART_CR3_DMAT); + + for (;;) { + while (!(rISR & USART_ISR_TXE)) + ; + + rTDR = 0x55; + } + + return 0; + + case 1: { + unsigned fails = 0; + + for (unsigned count = 0;; count++) { + uint16_t value = count & 0xffff; + + if (write((PX4IO_PAGE_TEST << 8) | PX4IO_P_TEST_LED, &value, 1) != 0) { + fails++; + } + + if (count >= 5000) { + syslog(LOG_INFO, "==== test 1 : %u failures ====\n", fails); + perf_print_counter(_pc_txns); + perf_print_counter(_pc_dmasetup); + perf_print_counter(_pc_retries); + perf_print_counter(_pc_timeouts); + perf_print_counter(_pc_crcerrs); + perf_print_counter(_pc_dmaerrs); + perf_print_counter(_pc_protoerrs); + perf_print_counter(_pc_uerrs); + perf_print_counter(_pc_idle); + perf_print_counter(_pc_badidle); + count = 0; + } + } + + return 0; + } + + case 2: + syslog(LOG_INFO, "test 2\n"); + return 0; + } + + default: + break; + } + + return -1; +} + +int +ArchPX4IOSerial::_bus_exchange(IOPacket *_packet) +{ + _current_packet = _packet; + + /* clear data that may be in the RDR and clear overrun error: */ + if (rISR & USART_ISR_RXNE) { + (void)rRDR; + } + + rICR = rISR & rISR_ERR_FLAGS_MASK; /* clear the flags */ + + /* start RX DMA */ + perf_begin(_pc_txns); + perf_begin(_pc_dmasetup); + + /* DMA setup time ~3µs */ + _rx_dma_status = _dma_status_waiting; + + /* + * Note that we enable circular buffer mode as a workaround for + * there being no API to disable the DMA FIFO. We need direct mode + * because otherwise when the line idle interrupt fires there + * will be packet bytes still in the DMA FIFO, and we will assume + * that the idle was spurious. + * + * XXX this should be fixed with a NuttX change. + */ + stm32_dmacfg_t rxdmacfg; + rxdmacfg.paddr = PX4IO_SERIAL_BASE + STM32_USART_RDR_OFFSET; + rxdmacfg.maddr = reinterpret_cast(_current_packet); + rxdmacfg.ndata = sizeof(*_current_packet); + rxdmacfg.cfg1 = (DMA_SCR_CIRC | + DMA_SCR_DIR_P2M | + DMA_SCR_MINC | + DMA_SCR_PSIZE_8BITS | + DMA_SCR_MSIZE_8BITS | + DMA_SCR_PBURST_SINGLE | + DMA_SCR_MBURST_SINGLE); + rxdmacfg.cfg2 = 0; + + + stm32_dmasetup(_rx_dma, &rxdmacfg); + + rCR3 |= USART_CR3_DMAR; + stm32_dmastart(_rx_dma, _dma_callback, this, false); + + /* Clean _current_packet, so DMA can see the data */ + up_clean_dcache((uintptr_t)_current_packet, + (uintptr_t)_current_packet + DMA_ALIGN_UP(sizeof(IOPacket))); + + /* start TX DMA - no callback if we also expect a reply */ + /* DMA setup time ~3µs */ + + stm32_dmacfg_t txdmacfg; + txdmacfg.paddr = PX4IO_SERIAL_BASE + STM32_USART_TDR_OFFSET; + txdmacfg.maddr = reinterpret_cast(_current_packet); + txdmacfg.ndata = PKT_SIZE(*_current_packet); + txdmacfg.cfg1 = (DMA_SCR_DIR_M2P | + DMA_SCR_MINC | + DMA_SCR_PSIZE_8BITS | + DMA_SCR_MSIZE_8BITS | + DMA_SCR_PBURST_SINGLE | + DMA_SCR_MBURST_SINGLE); + txdmacfg.cfg2 = 0; + + stm32_dmasetup(_tx_dma, &txdmacfg); + rCR3 |= USART_CR3_DMAT; + stm32_dmastart(_tx_dma, nullptr, nullptr, false); + //rCR1 &= ~USART_CR1_TE; + //rCR1 |= USART_CR1_TE; + + perf_end(_pc_dmasetup); + + /* compute the deadline for a 10ms timeout */ + struct timespec abstime; + clock_gettime(CLOCK_REALTIME, &abstime); + abstime.tv_nsec += 10 * 1000 * 1000; + + if (abstime.tv_nsec >= 1000 * 1000 * 1000) { + abstime.tv_sec++; + abstime.tv_nsec -= 1000 * 1000 * 1000; + } + + /* wait for the transaction to complete - 64 bytes @ 1.5Mbps ~426µs */ + int ret; + + for (;;) { + ret = sem_timedwait(&_completion_semaphore, &abstime); + + if (ret == OK) { + /* check for DMA errors */ + if (_rx_dma_status & DMA_STATUS_TEIF) { + perf_count(_pc_dmaerrs); + ret = -EIO; + break; + } + + /* check packet CRC - corrupt packet errors mean IO receive CRC error */ + uint8_t crc = _current_packet->crc; + _current_packet->crc = 0; + + if ((crc != crc_packet(_current_packet)) || (PKT_CODE(*_current_packet) == PKT_CODE_CORRUPT)) { + perf_count(_pc_crcerrs); + ret = -EIO; + break; + } + + /* successful txn (may still be reporting an error) */ + break; + } + + if (errno == ETIMEDOUT) { + /* something has broken - clear out any partial DMA state and reconfigure */ + _abort_dma(); + perf_count(_pc_timeouts); + perf_cancel(_pc_txns); /* don't count this as a transaction */ + break; + } + + /* we might? see this for EINTR */ + syslog(LOG_ERR, "unexpected ret %d/%d\n", ret, errno); + } + + /* reset DMA status */ + _rx_dma_status = _dma_status_inactive; + + /* update counters */ + perf_end(_pc_txns); + + return ret; +} + +void +ArchPX4IOSerial::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg) +{ + if (arg != nullptr) { + ArchPX4IOSerial *ps = reinterpret_cast(arg); + + ps->_do_rx_dma_callback(status); + } +} + +void +ArchPX4IOSerial::_do_rx_dma_callback(unsigned status) +{ + /* on completion of a reply, wake the waiter */ + if (_rx_dma_status == _dma_status_waiting) { + + /* check for packet overrun - this will occur after DMA completes */ + uint32_t sr = rISR; + + if (sr & (USART_ISR_ORE | USART_ISR_RXNE)) { + (void)rRDR; + rICR = sr & (USART_ISR_ORE | USART_ISR_RXNE); + status = DMA_STATUS_TEIF; + } + + /* save RX status */ + _rx_dma_status = status; + + /* disable UART DMA */ + rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR); + + /* complete now */ + px4_sem_post(&_completion_semaphore); + } +} + +int +ArchPX4IOSerial::_interrupt(int irq, void *context, void *arg) +{ + if (arg != nullptr) { + ArchPX4IOSerial *instance = reinterpret_cast(arg); + + instance->_do_interrupt(); + } + + return 0; +} + +void +ArchPX4IOSerial::_do_interrupt() +{ + uint32_t sr = rISR; /* get UART status register */ + + if (sr & USART_ISR_RXNE) { + (void)rRDR; /* read DR to clear RXNE */ + } + + rICR = sr & rISR_ERR_FLAGS_MASK; /* clear flags */ + + if (sr & (USART_ISR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */ + USART_ISR_NE | /* noise error - we have lost a byte due to noise */ + USART_ISR_FE)) { /* framing error - start/stop bit lost or line break */ + + /* + * If we are in the process of listening for something, these are all fatal; + * abort the DMA with an error. + */ + if (_rx_dma_status == _dma_status_waiting) { + _abort_dma(); + + perf_count(_pc_uerrs); + /* complete DMA as though in error */ + _do_rx_dma_callback(DMA_STATUS_TEIF); + + return; + } + + /* XXX we might want to use FE / line break as an out-of-band handshake ... handle it here */ + + /* don't attempt to handle IDLE if it's set - things went bad */ + return; + } + + if (sr & USART_ISR_IDLE) { + + /* if there is DMA reception going on, this is a short packet */ + if (_rx_dma_status == _dma_status_waiting) { + /* Invalidate _current_packet, so we get fresh data from RAM */ + up_invalidate_dcache((uintptr_t)_current_packet, + (uintptr_t)_current_packet + DMA_ALIGN_UP(sizeof(IOPacket))); + + /* verify that the received packet is complete */ + size_t length = sizeof(*_current_packet) - stm32_dmaresidual(_rx_dma); + + if ((length < 1) || (length < PKT_SIZE(*_current_packet))) { + perf_count(_pc_badidle); + + /* stop the receive DMA */ + stm32_dmastop(_rx_dma); + + /* complete the short reception */ + _do_rx_dma_callback(DMA_STATUS_TEIF); + return; + } + + perf_count(_pc_idle); + + /* stop the receive DMA */ + stm32_dmastop(_rx_dma); + + /* complete the short reception */ + _do_rx_dma_callback(DMA_STATUS_TCIF); + } + } +} + +void +ArchPX4IOSerial::_abort_dma() +{ + /* stop DMA */ + stm32_dmastop(_tx_dma); + stm32_dmastop(_rx_dma); + + /* disable UART DMA */ + rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR); + + /* clear data that may be in the RDR and clear overrun error: */ + if (rISR & USART_ISR_RXNE) { + (void)rRDR; + } + + rICR = rISR & rISR_ERR_FLAGS_MASK; /* clear the flags */ +} + diff --git a/src/drivers/adc/adc.cpp b/src/drivers/adc/adc.cpp index da4dbf135d..f6ad5112d8 100644 --- a/src/drivers/adc/adc.cpp +++ b/src/drivers/adc/adc.cpp @@ -37,7 +37,7 @@ * Driver for an ADC. * */ - +#include #include #include #include @@ -82,9 +82,9 @@ private: * Sample a single channel and return the measured value. * * @param channel The channel to sample. - * @return The sampled value, or 0xffff if sampling failed. + * @return The sampled value, or UINT32_MAX if sampling failed. */ - uint16_t sample(unsigned channel); + uint32_t sample(unsigned channel); void update_adc_report(hrt_abstime now); void update_system_power(hrt_abstime now); @@ -233,7 +233,8 @@ ADC::update_adc_report(hrt_abstime now) for (unsigned i = 0; i < max_num; i++) { adc.channel_id[i] = _samples[i].am_channel; - adc.channel_value[i] = _samples[i].am_data * 3.3f / 4096.0f; + adc.channel_value[i] = _samples[i].am_data * 3.3f / px4_arch_adc_dn_fullcount(); + ; } _to_adc_report.publish(adc); @@ -258,7 +259,7 @@ ADC::update_system_power(hrt_abstime now) if (_samples[i].am_channel == ADC_SCALED_V5_SENSE) { // it is 2:1 scaled - system_power.voltage5v_v = _samples[i].am_data * (ADC_V5_V_FULL_SCALE / 4096.0f); + system_power.voltage5v_v = _samples[i].am_data * (ADC_V5_V_FULL_SCALE / px4_arch_adc_dn_fullcount()); cnt--; } else @@ -267,7 +268,7 @@ ADC::update_system_power(hrt_abstime now) { if (_samples[i].am_channel == ADC_SCALED_V3V3_SENSORS_SENSE) { // it is 2:1 scaled - system_power.voltage3v3_v = _samples[i].am_data * (ADC_3V3_SCALE * (3.3f / 4096.0f)); + system_power.voltage3v3_v = _samples[i].am_data * (ADC_3V3_SCALE * (3.3f / px4_arch_adc_dn_fullcount())); system_power.v3v3_valid = 1; cnt--; } @@ -323,13 +324,13 @@ ADC::update_system_power(hrt_abstime now) #endif // BOARD_ADC_USB_CONNECTED } -uint16_t +uint32_t ADC::sample(unsigned channel) { perf_begin(_sample_perf); - uint16_t result = px4_arch_adc_sample(_base_address, channel); + uint32_t result = px4_arch_adc_sample(_base_address, channel); - if (result == 0xffff) { + if (result == UINT32_MAX) { PX4_ERR("sample timeout"); } diff --git a/src/drivers/camera_trigger/interfaces/src/gpio.cpp b/src/drivers/camera_trigger/interfaces/src/gpio.cpp index 8104fc189b..8cb13d5c9c 100644 --- a/src/drivers/camera_trigger/interfaces/src/gpio.cpp +++ b/src/drivers/camera_trigger/interfaces/src/gpio.cpp @@ -3,7 +3,7 @@ #include "gpio.h" #include -constexpr uint32_t CameraInterfaceGPIO::_gpios[6]; +constexpr uint32_t CameraInterfaceGPIO::_gpios[ngpios]; CameraInterfaceGPIO::CameraInterfaceGPIO(): CameraInterface(), @@ -25,7 +25,7 @@ void CameraInterfaceGPIO::setup() { for (unsigned i = 0, t = 0; i < arraySize(_pins); i++) { - // Pin range is from 1 to 6, indexes are 0 to 5 + // Pin range is from 1 to 5 or 6, indexes are 0 to 4 or 5 if (_pins[i] >= 0 && _pins[i] < (int)arraySize(_gpios)) { uint32_t gpio = _gpios[_pins[i]]; @@ -50,9 +50,17 @@ void CameraInterfaceGPIO::trigger(bool trigger_on_true) void CameraInterfaceGPIO::info() { - PX4_INFO("GPIO trigger mode, pins enabled : [%d][%d][%d][%d][%d][%d], polarity : %s", - _pins[5], _pins[4], _pins[3], _pins[2], _pins[1], _pins[0], - _trigger_invert ? "ACTIVE_LOW" : "ACTIVE_HIGH"); + if (ngpios == 6) { + PX4_INFO("GPIO trigger mode, pins enabled : [%d][%d][%d][%d][%d][%d], polarity : %s", + _pins[5], _pins[4], _pins[3], _pins[2], _pins[1], _pins[0], + _trigger_invert ? "ACTIVE_LOW" : "ACTIVE_HIGH"); + } + + if (ngpios == 5) { + PX4_INFO("GPIO trigger mode, pins enabled : [%d][%d][%d][%d][%d], polarity : %s", + _pins[4], _pins[3], _pins[2], _pins[1], _pins[0], + _trigger_invert ? "ACTIVE_LOW" : "ACTIVE_HIGH"); + } } #endif /* ifdef __PX4_NUTTX */ diff --git a/src/drivers/camera_trigger/interfaces/src/gpio.h b/src/drivers/camera_trigger/interfaces/src/gpio.h index 38150d1409..9cb227efeb 100644 --- a/src/drivers/camera_trigger/interfaces/src/gpio.h +++ b/src/drivers/camera_trigger/interfaces/src/gpio.h @@ -21,6 +21,11 @@ public: void trigger(bool trigger_on_true); void info(); +#if defined(GPIO_GPIO5_OUTPUT) + static const int ngpios = 6; +#else + static const int ngpios = 5; +#endif private: @@ -30,13 +35,15 @@ private: bool _trigger_invert; - static constexpr uint32_t _gpios[6] = { + static constexpr uint32_t _gpios[ngpios] = { GPIO_GPIO0_OUTPUT, GPIO_GPIO1_OUTPUT, GPIO_GPIO2_OUTPUT, GPIO_GPIO3_OUTPUT, GPIO_GPIO4_OUTPUT, +#if defined(GPIO_GPIO5_OUTPUT) GPIO_GPIO5_OUTPUT +#endif }; uint32_t _triggers[arraySize(_gpios)]; diff --git a/src/drivers/drv_adc.h b/src/drivers/drv_adc.h index 3e7e984eaf..538384c3d5 100644 --- a/src/drivers/drv_adc.h +++ b/src/drivers/drv_adc.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (C) 2012, 2019 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -78,14 +78,19 @@ void px4_arch_adc_uninit(uint32_t base_address); * Read a sample from the ADC * @param base_address architecture-specific address to specify the ADC * @param channel specify the channel - * @return sample, 0xffff on error + * @return sample, 0xffffffff on error */ -uint16_t px4_arch_adc_sample(uint32_t base_address, unsigned channel); +uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel); /** * Get the temperature sensor channel bitmask */ uint32_t px4_arch_adc_temp_sensor_mask(void); +/** + * Get the adc digital number full count + */ +uint32_t px4_arch_adc_dn_fullcount(void); + __END_DECLS diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 9494047be2..5c5f649c7b 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -83,6 +83,8 @@ struct GPS_Sat_Info { struct satellite_info_s _data; }; +static constexpr int TASK_STACK_SIZE = 1620; + class GPS : public ModuleBase { @@ -1069,7 +1071,7 @@ int GPS::task_spawn(int argc, char *argv[], Instance instance) } int task_id = px4_task_spawn_cmd("gps", SCHED_DEFAULT, - SCHED_PRIORITY_SLOW_DRIVER, 1700, + SCHED_PRIORITY_SLOW_DRIVER, TASK_STACK_SIZE, entry_point, (char *const *)argv); if (task_id < 0) { diff --git a/src/drivers/lights/blinkm/CMakeLists.txt b/src/drivers/lights/blinkm/CMakeLists.txt index 67d2d4fca7..736f9cc83c 100644 --- a/src/drivers/lights/blinkm/CMakeLists.txt +++ b/src/drivers/lights/blinkm/CMakeLists.txt @@ -33,6 +33,7 @@ px4_add_module( MODULE drivers__blinkm MAIN blinkm + STACK_MAIN 1240 COMPILE_FLAGS SRCS blinkm.cpp diff --git a/src/drivers/pwm_input/pwm_input.cpp b/src/drivers/pwm_input/pwm_input.cpp index 752d57e1b2..a1ee7012f9 100644 --- a/src/drivers/pwm_input/pwm_input.cpp +++ b/src/drivers/pwm_input/pwm_input.cpp @@ -94,70 +94,14 @@ #error PWMIN defines are needed in board_config.h for this board #endif -/* PWMIN configuration */ -#if PWMIN_TIMER == 1 -# define PWMIN_TIMER_BASE STM32_TIM1_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB2ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB2ENR_TIM1EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM1CC -# define PWMIN_TIMER_CLOCK STM32_APB2_TIM1_CLKIN -#elif PWMIN_TIMER == 2 -# define PWMIN_TIMER_BASE STM32_TIM2_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB1ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB1ENR_TIM2EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM2 -# define PWMIN_TIMER_CLOCK STM32_APB1_TIM2_CLKIN -#elif PWMIN_TIMER == 3 -# define PWMIN_TIMER_BASE STM32_TIM3_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB1ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB1ENR_TIM3EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM3 -# define PWMIN_TIMER_CLOCK STM32_APB1_TIM3_CLKIN -#elif PWMIN_TIMER == 4 -# define PWMIN_TIMER_BASE STM32_TIM4_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB1ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB1ENR_TIM4EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM4 -# define PWMIN_TIMER_CLOCK STM32_APB1_TIM4_CLKIN -#elif PWMIN_TIMER == 5 -# define PWMIN_TIMER_BASE STM32_TIM5_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB1ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB1ENR_TIM5EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM5 -# define PWMIN_TIMER_CLOCK STM32_APB1_TIM5_CLKIN -#elif PWMIN_TIMER == 8 -# define PWMIN_TIMER_BASE STM32_TIM8_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB2ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB2ENR_TIM8EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM8CC -# define PWMIN_TIMER_CLOCK STM32_APB2_TIM8_CLKIN -#elif PWMIN_TIMER == 9 -# define PWMIN_TIMER_BASE STM32_TIM9_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB2ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB2ENR_TIM9EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM1BRK -# define PWMIN_TIMER_CLOCK STM32_APB2_TIM9_CLKIN -#elif PWMIN_TIMER == 10 -# define PWMIN_TIMER_BASE STM32_TIM10_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB2ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM1UP -# define PWMIN_TIMER_CLOCK STM32_APB2_TIM10_CLKIN -#elif PWMIN_TIMER == 11 -# define PWMIN_TIMER_BASE STM32_TIM11_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB2ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM -# define PWMIN_TIMER_CLOCK STM32_APB2_TIM11_CLKIN -#elif PWMIN_TIMER == 12 -# define PWMIN_TIMER_BASE STM32_TIM12_BASE -# define PWMIN_TIMER_POWER_REG STM32_RCC_APB1ENR -# define PWMIN_TIMER_POWER_BIT RCC_APB1ENR_TIM12EN -# define PWMIN_TIMER_VECTOR STM32_IRQ_TIM8BRK -# define PWMIN_TIMER_CLOCK STM32_APB1_TIM12_CLKIN -#else -# error PWMIN_TIMER must be a value between 1 and 12 -#endif +/* Get the timer defines */ +#define INPUT_TIMER PWMIN_TIMER +#include "timer_registers.h" +#define PWMIN_TIMER_BASE TIMER_BASE +#define PWMIN_TIMER_CLOCK TIMER_CLOCK +#define PWMIN_TIMER_POWER_REG TIMER_CLOCK_POWER_REG +#define PWMIN_TIMER_POWER_BIT TIMER_CLOCK_POWER_BIT +#define PWMIN_TIMER_VECTOR TIMER_IRQ_REG /* * HRT clock must be at least 1MHz diff --git a/src/drivers/pwm_input/timer_registers.h b/src/drivers/pwm_input/timer_registers.h new file mode 100644 index 0000000000..f48c67b05f --- /dev/null +++ b/src/drivers/pwm_input/timer_registers.h @@ -0,0 +1,188 @@ +/**************************************************************************** + * + * Copyright (C) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file timer_registers.h + * + * Get architecture-specific timer register defines. + * Usage: + * #define INPUT_TIMER + * #include "timer_registers.h" + * # define _TIMER_BASE TIMER_BASE + * # define _TIMER_CLOCK TIMER_CLOCK + * # define _TIMER_POWER_REG TIMER_CLOCK_POWER_REG + * # define _TIMER_POWER_BIT TIMER_CLOCK_POWER_BIT + * # define _TIMER_VECTOR TIMER_IRQ_REG + * + */ + +#include + +#ifndef INPUT_TIMER +# error "need to define INPUT_TIMER to use this header" +#endif + +#ifdef TIMER_BASE +#undef TIMER_BASE +#endif +#ifdef TIMER_CLOCK_POWER_REG +#undef TIMER_CLOCK_POWER_REG +#endif +#ifdef TIMER_CLOCK_POWER_BIT +#undef TIMER_CLOCK_POWER_BIT +#endif +#ifdef TIMER_CLOCK +#undef TIMER_CLOCK +#endif +#ifdef TIMER_IRQ_REG +#undef TIMER_IRQ_REG +#endif + + + +#if defined(CONFIG_ARCH_CHIP_STM32H7) + +#if INPUT_TIMER == 1 +# define TIMER_BASE STM32_TIM1_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB2ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB2ENR_TIM1EN +# define TIMER_IRQ_REG STM32_IRQ_TIMCC +# define TIMER_CLOCK STM32_APB2_TIM1_CLKIN +#elif INPUT_TIMER == 2 +# define TIMER_BASE STM32_TIM2_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1LENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1LENR_TIM2EN +# define TIMER_IRQ_REG STM32_IRQ_TIM2 +# define TIMER_CLOCK STM32_APB1_TIM2_CLKIN +#elif INPUT_TIMER == 3 +# define TIMER_BASE STM32_TIM3_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1LENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1LENR_TIM3EN +# define TIMER_IRQ_REG STM32_IRQ_TIM3 +# define TIMER_CLOCK STM32_APB1_TIM3_CLKIN +#elif INPUT_TIMER == 4 +# define TIMER_BASE STM32_TIM4_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1LENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1LENR_TIM4EN +# define TIMER_IRQ_REG STM32_IRQ_TIM4 +# define TIMER_CLOCK STM32_APB1_TIM4_CLKIN +#elif INPUT_TIMER == 5 +# define TIMER_BASE STM32_TIM5_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1LENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1LENR_TIM5EN +# define TIMER_IRQ_REG STM32_IRQ_TIM5 +# define TIMER_CLOCK STM32_APB1_TIM5_CLKIN +#elif INPUT_TIMER == 8 +# define TIMER_BASE STM32_TIM8_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB2ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB2ENR_TIM8EN +# define TIMER_IRQ_REG STM32_IRQ_TIM8CC +# define TIMER_CLOCK STM32_APB2_TIM8_CLKIN +#elif INPUT_TIMER == 12 +# define TIMER_BASE STM32_TIM12_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1LENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1LENR_TIM12EN +# define TIMER_IRQ_REG STM32_IRQ_TIM12 +# define TIMER_CLOCK STM32_APB1_TIM12_CLKIN +#else +# error INPUT_TIMER must be a value between 1 and 12 +#endif + + +#else // F4, F7 + +#if INPUT_TIMER == 1 +# define TIMER_BASE STM32_TIM1_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB2ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB2ENR_TIM1EN +# define TIMER_IRQ_REG STM32_IRQ_TIM1CC +# define TIMER_CLOCK STM32_APB2_TIM1_CLKIN +#elif INPUT_TIMER == 2 +# define TIMER_BASE STM32_TIM2_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1ENR_TIM2EN +# define TIMER_IRQ_REG STM32_IRQ_TIM2 +# define TIMER_CLOCK STM32_APB1_TIM2_CLKIN +#elif INPUT_TIMER == 3 +# define TIMER_BASE STM32_TIM3_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1ENR_TIM3EN +# define TIMER_IRQ_REG STM32_IRQ_TIM3 +# define TIMER_CLOCK STM32_APB1_TIM3_CLKIN +#elif INPUT_TIMER == 4 +# define TIMER_BASE STM32_TIM4_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1ENR_TIM4EN +# define TIMER_IRQ_REG STM32_IRQ_TIM4 +# define TIMER_CLOCK STM32_APB1_TIM4_CLKIN +#elif INPUT_TIMER == 5 +# define TIMER_BASE STM32_TIM5_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1ENR_TIM5EN +# define TIMER_IRQ_REG STM32_IRQ_TIM5 +# define TIMER_CLOCK STM32_APB1_TIM5_CLKIN +#elif INPUT_TIMER == 8 +# define TIMER_BASE STM32_TIM8_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB2ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB2ENR_TIM8EN +# define TIMER_IRQ_REG STM32_IRQ_TIM8CC +# define TIMER_CLOCK STM32_APB2_TIM8_CLKIN +#elif INPUT_TIMER == 9 +# define TIMER_BASE STM32_TIM9_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB2ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB2ENR_TIM9EN +# define TIMER_IRQ_REG STM32_IRQ_TIM1BRK +# define TIMER_CLOCK STM32_APB2_TIM9_CLKIN +#elif INPUT_TIMER == 10 +# define TIMER_BASE STM32_TIM10_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB2ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB2ENR_TIM10EN +# define TIMER_IRQ_REG STM32_IRQ_TIM1UP +# define TIMER_CLOCK STM32_APB2_TIM10_CLKIN +#elif INPUT_TIMER == 11 +# define TIMER_BASE STM32_TIM11_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB2ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB2ENR_TIM11EN +# define TIMER_IRQ_REG STM32_IRQ_TIM1TRGCOM +# define TIMER_CLOCK STM32_APB2_TIM11_CLKIN +#elif INPUT_TIMER == 12 +# define TIMER_BASE STM32_TIM12_BASE +# define TIMER_CLOCK_POWER_REG STM32_RCC_APB1ENR +# define TIMER_CLOCK_POWER_BIT RCC_APB1ENR_TIM12EN +# define TIMER_IRQ_REG STM32_IRQ_TIM8BRK +# define TIMER_CLOCK STM32_APB1_TIM12_CLKIN +#else +# error INPUT_TIMER must be a value between 1 and 12 +#endif + +#endif diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index e025eb30d2..acd521c013 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -1146,9 +1146,12 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) break; } +#endif +#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 5 + /* FALLTHROUGH */ case PWM_SERVO_SET(4): - if (_mode < MODE_5PWM1CAP) { + if (_mode < MODE_5PWM) { ret = -EINVAL; break; } @@ -1216,9 +1219,12 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) break; } +#endif +#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 5 + /* FALLTHROUGH */ case PWM_SERVO_GET(4): - if (_mode < MODE_5PWM1CAP) { + if (_mode < MODE_5PWM) { ret = -EINVAL; break; } @@ -1249,8 +1255,10 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) case PWM_SERVO_GET_RATEGROUP(1): case PWM_SERVO_GET_RATEGROUP(2): case PWM_SERVO_GET_RATEGROUP(3): -#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 6 +#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 5 case PWM_SERVO_GET_RATEGROUP(4): +#endif +#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 6 case PWM_SERVO_GET_RATEGROUP(5): #endif #if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 8 @@ -1677,6 +1685,9 @@ PX4FMU::fmu_new_mode(PortMode new_mode) /* select 4-pin PWM mode */ servo_mode = PX4FMU::MODE_4PWM; #endif +#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM == 5 + servo_mode = PX4FMU::MODE_5PWM; +#endif #if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM == 6 servo_mode = PX4FMU::MODE_6PWM; #endif @@ -2109,6 +2120,9 @@ int PX4FMU::custom_command(int argc, char *argv[]) } else if (!strcmp(verb, "mode_pwm6")) { new_mode = PORT_PWM6; +#endif +#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 5 + } else if (!strcmp(verb, "mode_pwm5")) { new_mode = PORT_PWM5; diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index a394e6c66c..20a3c210a9 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2822,6 +2822,7 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) } /* reboot into bootloader - arg must be PX4IO_REBOOT_BL_MAGIC */ + usleep(1); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_REBOOT_BL, arg); // we don't expect a reply from this operation ret = OK; diff --git a/src/drivers/uavcanesc/led.cpp b/src/drivers/uavcanesc/led.cpp index 69bac91307..fcadc5c4ee 100644 --- a/src/drivers/uavcanesc/led.cpp +++ b/src/drivers/uavcanesc/led.cpp @@ -36,7 +36,7 @@ #include #include -#include "chip/stm32_tim.h" +#include "hardware/stm32_tim.h" #include "led.hpp" diff --git a/src/drivers/uavcannode/led.cpp b/src/drivers/uavcannode/led.cpp index 69bac91307..fcadc5c4ee 100644 --- a/src/drivers/uavcannode/led.cpp +++ b/src/drivers/uavcannode/led.cpp @@ -36,7 +36,7 @@ #include #include -#include "chip/stm32_tim.h" +#include "hardware/stm32_tim.h" #include "led.hpp" diff --git a/src/modules/dataman/dataman.cpp b/src/modules/dataman/dataman.cpp index 7239fb679c..00d72d92b7 100644 --- a/src/modules/dataman/dataman.cpp +++ b/src/modules/dataman/dataman.cpp @@ -72,6 +72,8 @@ __BEGIN_DECLS __EXPORT int dataman_main(int argc, char *argv[]); __END_DECLS +static constexpr int TASK_STACK_SIZE = 1220; + /* Private File based Operations */ static ssize_t _file_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count); @@ -1446,7 +1448,8 @@ start() px4_sem_setprotocol(&g_init_sema, SEM_PRIO_NONE); /* start the worker thread with low priority for disk IO */ - if ((task = px4_task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 10, 1200, task_main, nullptr)) < 0) { + if ((task = px4_task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 10, TASK_STACK_SIZE, task_main, + nullptr)) < 0) { px4_sem_destroy(&g_init_sema); PX4_ERR("task start failed"); return -1; diff --git a/src/systemcmds/bl_update/bl_update.c b/src/systemcmds/bl_update/bl_update.c index a59b260b8a..0c92a92bf2 100644 --- a/src/systemcmds/bl_update/bl_update.c +++ b/src/systemcmds/bl_update/bl_update.c @@ -58,7 +58,9 @@ __EXPORT int bl_update_main(int argc, char *argv[]); -#if defined (CONFIG_STM32_STM32F4XXX) || defined (CONFIG_ARCH_CHIP_STM32F7) +#if defined (CONFIG_STM32_STM32F4XXX) || defined (CONFIG_ARCH_CHIP_STM32F7) || \ + defined (CONFIG_ARCH_CHIP_STM32H7) + static int setopt(void); static void print_usage(const char *reason) @@ -81,7 +83,8 @@ static void print_usage(const char *reason) int bl_update_main(int argc, char *argv[]) { -#if !(defined (CONFIG_STM32_STM32F4XXX) || defined (CONFIG_ARCH_CHIP_STM32F7)) +#if !(defined (CONFIG_STM32_STM32F4XXX) || defined (CONFIG_ARCH_CHIP_STM32F7) \ + || defined (CONFIG_ARCH_CHIP_STM32H7)) PX4_ERR("Not supported on this HW"); return 1; }