forked from Archive/PX4-Autopilot
boards: cuav nora/x7pro don't have low speed external (LSE) oscillator
This commit is contained in:
parent
a11d2207e4
commit
440e72e697
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific specific board MAVLink startup script.
|
||||
# board specific board MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -60,7 +60,7 @@
|
|||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 32768
|
||||
#define STM32_LSE_FREQUENCY 0
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
|
|
|
@ -172,6 +172,7 @@ CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
|||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC1=y
|
||||
|
|
|
@ -48,7 +48,6 @@
|
|||
#include "arm_internal.h"
|
||||
#include <px4_platform_common/init.h>
|
||||
|
||||
|
||||
extern int sercon_main(int c, char **argv);
|
||||
|
||||
__EXPORT void board_on_reset(int status) {}
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# CUAV X7Pro specific board defaults
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
#
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific specific board MAVLink startup script.
|
||||
# board specific board MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -60,7 +60,7 @@
|
|||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 32768
|
||||
#define STM32_LSE_FREQUENCY 0
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
|
|
|
@ -172,6 +172,7 @@ CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
|||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC1=y
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* CUAV X7Pro internal definitions
|
||||
* Board internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
|
Loading…
Reference in New Issue