forked from Archive/PX4-Autopilot
NuttX based PX4 bootloader
stm32h7 booloader:Obey VBUS input stm32h7 booloader:Fully deinit systic
This commit is contained in:
parent
78944a70c3
commit
522ed2d99b
|
@ -171,6 +171,9 @@ function(px4_add_common_flags)
|
|||
${PX4_BINARY_DIR}
|
||||
${PX4_BINARY_DIR}/src/lib
|
||||
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
|
||||
${PX4_SOURCE_DIR}/platforms/${PX4_PLATFORM}/src/bootloader
|
||||
endif()
|
||||
${PX4_SOURCE_DIR}/platforms/${PX4_PLATFORM}/src/px4/${PX4_CHIP_MANUFACTURER}/${PX4_CHIP}/include
|
||||
${PX4_SOURCE_DIR}/platforms/${PX4_PLATFORM}/src/px4/common/include
|
||||
${PX4_SOURCE_DIR}/platforms/common/include
|
||||
|
|
|
@ -47,6 +47,16 @@ get_property(module_libraries GLOBAL PROPERTY PX4_MODULE_LIBRARIES)
|
|||
add_subdirectory(NuttX ${PX4_BINARY_DIR}/NuttX)
|
||||
|
||||
set(nuttx_libs)
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
|
||||
set(SCRIPT_PREFIX ${PX4_BOARD_LABEL}_)
|
||||
add_subdirectory(src/bootloader)
|
||||
list(APPEND nuttx_libs
|
||||
bootloader
|
||||
bootloader_lib
|
||||
drivers_board
|
||||
)
|
||||
endif()
|
||||
|
||||
list(APPEND nuttx_libs
|
||||
nuttx_apps
|
||||
nuttx_arch
|
||||
|
@ -94,7 +104,7 @@ target_link_libraries(px4 PRIVATE
|
|||
-fno-exceptions
|
||||
-fno-rtti
|
||||
|
||||
-Wl,--script=${PX4_BINARY_DIR_CYG}/NuttX/nuttx-config/scripts/script.ld
|
||||
-Wl,--script=${PX4_BINARY_DIR_CYG}/NuttX/nuttx-config/scripts/${SCRIPT_PREFIX}script.ld
|
||||
-Wl,-Map=${PX4_CONFIG}.map
|
||||
-Wl,--warn-common
|
||||
-Wl,--gc-sections
|
||||
|
@ -205,6 +215,9 @@ if(NOT PX4_BUILD MATCHES "px4_io-v2")
|
|||
elseif(CONFIG_ARCH_CHIP_STM32F777NI)
|
||||
set(DEBUG_DEVICE "STM32F777NI")
|
||||
set(DEBUG_SVD_FILE "STM32F7x7.svd")
|
||||
elseif(CONFIG_ARCH_CHIP_STM32H743ZI)
|
||||
set(DEBUG_DEVICE "STM32H743ZI")
|
||||
set(DEBUG_SVD_FILE "STM32H7x3.svd")
|
||||
endif()
|
||||
|
||||
file(GLOB_RECURSE DEBUG_SVD_FILE_PATH ${CMAKE_SOURCE_DIR}/../cmsis-svd/*/${DEBUG_SVD_FILE})
|
||||
|
|
|
@ -0,0 +1,40 @@
|
|||
############################################################################
|
||||
#
|
||||
# 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_library(bootloader
|
||||
bl.c
|
||||
${PX4_CHIP}/main.c
|
||||
)
|
||||
|
||||
add_subdirectory(lib)
|
||||
add_dependencies(bootloader prebuild_targets)
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,130 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2014 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 bl.h
|
||||
*
|
||||
* Common bootloader definitions.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/*****************************************************************************
|
||||
* Generic bootloader functions.
|
||||
*/
|
||||
|
||||
/* enum for whether bootloading via USB or USART */
|
||||
enum {
|
||||
NONE,
|
||||
USART,
|
||||
USB
|
||||
};
|
||||
|
||||
/* board info forwarded from board-specific code to booloader */
|
||||
struct boardinfo {
|
||||
uint32_t board_type;
|
||||
uint32_t board_rev;
|
||||
uint32_t fw_size;
|
||||
uint32_t systick_mhz; /* systick input clock */
|
||||
|
||||
} __attribute__((packed));
|
||||
|
||||
extern struct boardinfo board_info;
|
||||
|
||||
extern void jump_to_app(void);
|
||||
extern void bootloader(unsigned timeout);
|
||||
extern void delay(unsigned msec);
|
||||
|
||||
#define BL_WAIT_MAGIC 0x19710317 /* magic number in PWR regs to wait in bootloader */
|
||||
|
||||
/* generic timers */
|
||||
#define NTIMERS 4
|
||||
#define TIMER_BL_WAIT 0
|
||||
#define TIMER_CIN 1
|
||||
#define TIMER_LED 2
|
||||
#define TIMER_DELAY 3
|
||||
extern volatile unsigned timer[NTIMERS]; /* each timer decrements every millisecond if > 0 */
|
||||
|
||||
/* generic receive buffer for async reads */
|
||||
extern void buf_put(uint8_t b);
|
||||
extern int buf_get(void);
|
||||
|
||||
/*****************************************************************************
|
||||
* Chip/board functions.
|
||||
*/
|
||||
|
||||
/* LEDs */
|
||||
#define LED_ACTIVITY 1
|
||||
#define LED_BOOTLOADER 2
|
||||
|
||||
#ifdef BOOT_DELAY_ADDRESS
|
||||
# define BOOT_DELAY_SIGNATURE1 0x92c2ecff
|
||||
# define BOOT_DELAY_SIGNATURE2 0xc5057d5d
|
||||
# define BOOT_DELAY_MAX 30
|
||||
#endif
|
||||
|
||||
#define MAX_DES_LENGTH 20
|
||||
|
||||
#define arraySize(a) (sizeof((a))/sizeof(((a)[0])))
|
||||
extern void led_on(unsigned led);
|
||||
extern void led_off(unsigned led);
|
||||
extern void led_toggle(unsigned led);
|
||||
|
||||
/* flash helpers from main_*.c */
|
||||
extern void board_deinit(void);
|
||||
extern uint32_t board_get_devices(void);
|
||||
extern void clock_deinit(void);
|
||||
extern uint32_t flash_func_sector_size(unsigned sector);
|
||||
extern void flash_func_erase_sector(unsigned sector);
|
||||
extern void flash_func_write_word(uint32_t address, uint32_t word);
|
||||
extern uint32_t flash_func_read_word(uint32_t address);
|
||||
extern uint32_t flash_func_read_otp(uint32_t address);
|
||||
extern uint32_t flash_func_read_sn(uint32_t address);
|
||||
extern void arch_flash_lock(void);
|
||||
extern void arch_flash_unlock(void);
|
||||
extern void arch_setvtor(uint32_t address);
|
||||
void arch_systic_init(void);
|
||||
void arch_systic_deinit(void);
|
||||
|
||||
extern uint32_t get_mcu_id(void);
|
||||
int get_mcu_desc(int max, uint8_t *revstr);
|
||||
extern int check_silicon(void);
|
||||
|
||||
/*****************************************************************************
|
||||
* Interface in/output.
|
||||
*/
|
||||
|
||||
extern void cinit(void *config, uint8_t interface);
|
||||
extern void cfini(void);
|
||||
extern int cin(uint32_t devices);
|
||||
extern void cout(uint8_t *buf, unsigned len);
|
|
@ -0,0 +1,46 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2014 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 cdcacm.h
|
||||
*
|
||||
* cdcacm bootloader definitions.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
|
||||
extern void usb_cinit(void *config);
|
||||
extern void usb_cfini(void);
|
||||
extern int usb_cin(void);
|
||||
extern void usb_cout(uint8_t *buf, unsigned len);
|
|
@ -0,0 +1,41 @@
|
|||
############################################################################
|
||||
#
|
||||
# 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_library(bootloader_lib
|
||||
systick.c
|
||||
cdcacm.c
|
||||
uart.c
|
||||
flash_cache.c
|
||||
)
|
||||
|
||||
add_dependencies(bootloader_lib prebuild_targets)
|
|
@ -0,0 +1,138 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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 "cdcacm.h"
|
||||
#include <string.h>
|
||||
#include<stdio.h>
|
||||
#include<fcntl.h>
|
||||
#include<termios.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/boardctl.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <debug.h>
|
||||
#include "cdcacm.h"
|
||||
|
||||
//#define SERIAL_TRACE
|
||||
|
||||
int g_usb_df = -1;
|
||||
char *g_device = 0;
|
||||
char *g_init = 0;
|
||||
|
||||
#if defined(SERIAL_TRACE)
|
||||
int in = 0;
|
||||
int out = 0;
|
||||
char in_trace[254];
|
||||
char out_trace[254];
|
||||
#endif
|
||||
|
||||
void usb_cinit(void *config)
|
||||
{
|
||||
#if defined(SERIAL_TRACE)
|
||||
in = 0;
|
||||
out = 0;
|
||||
memset(in_trace, 0, sizeof(in_trace));
|
||||
memset(out_trace, 0, sizeof(out_trace));
|
||||
#endif
|
||||
g_init = strdup(config ? (char *) config : "");
|
||||
char *pt = strtok((char *) g_init, ",");
|
||||
|
||||
if (pt != NULL) {
|
||||
g_device = pt;
|
||||
}
|
||||
|
||||
int fd = open(g_device, O_RDWR | O_NONBLOCK);
|
||||
|
||||
if (fd >= 0) {
|
||||
g_usb_df = fd;
|
||||
free(g_init);
|
||||
}
|
||||
}
|
||||
void usb_cfini(void)
|
||||
{
|
||||
close(g_usb_df);
|
||||
g_usb_df = -1;
|
||||
}
|
||||
int usb_cin(void)
|
||||
{
|
||||
int c = -1;
|
||||
|
||||
if (g_usb_df < 0) {
|
||||
|
||||
int fd = open(g_device, O_RDWR | O_NONBLOCK);
|
||||
|
||||
if (fd < 0) {
|
||||
return c;
|
||||
}
|
||||
|
||||
g_usb_df = fd;
|
||||
free(g_init);
|
||||
}
|
||||
|
||||
char b;
|
||||
|
||||
if (read(g_usb_df, &b, 1) == 1) {
|
||||
c = b;
|
||||
#if defined(SERIAL_TRACE)
|
||||
in_trace[in] = b;
|
||||
in++;
|
||||
in &= 255;
|
||||
#endif
|
||||
}
|
||||
|
||||
return c;
|
||||
}
|
||||
void usb_cout(uint8_t *buf, unsigned len)
|
||||
{
|
||||
uint32_t timeout = 1000;
|
||||
|
||||
for (unsigned i = 0; i < len; i++) {
|
||||
while (timeout) {
|
||||
if (write(g_usb_df, &buf[i], 1) == 1) {
|
||||
#if defined(SERIAL_TRACE)
|
||||
out_trace[out] = buf[i];
|
||||
out++;
|
||||
out &= 255;
|
||||
#endif
|
||||
timeout = 1000;
|
||||
break;
|
||||
|
||||
} else {
|
||||
if (timeout-- == 0) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,159 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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 <string.h>
|
||||
#include "flash_cache.h"
|
||||
|
||||
#include "hw_config.h"
|
||||
|
||||
#include <nuttx/progmem.h>
|
||||
|
||||
|
||||
flash_cache_line_t flash_cache[FC_NUMBER_LINES];
|
||||
|
||||
|
||||
static inline void fcl_reset(flash_cache_line_t *fcl)
|
||||
{
|
||||
memset(fcl, 0xff, sizeof(flash_cache_line_t));
|
||||
}
|
||||
|
||||
inline void fc_reset(void)
|
||||
{
|
||||
for (unsigned w = 0; w < FC_NUMBER_LINES; w++) {
|
||||
fcl_reset(&flash_cache[w]);
|
||||
}
|
||||
|
||||
flash_cache[0].start_address = APP_LOAD_ADDRESS;
|
||||
}
|
||||
|
||||
static inline flash_cache_line_t *fc_line_select(uint32_t address)
|
||||
{
|
||||
for (unsigned w = 0; w < FC_NUMBER_LINES; w++) {
|
||||
if (flash_cache[w].start_address == (address & FC_ADDRESS_MASK)) {
|
||||
return &flash_cache[w];
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
inline int fc_is_dirty(flash_cache_line_t *fl)
|
||||
{
|
||||
return fl->index != FC_CLEAN;
|
||||
}
|
||||
|
||||
|
||||
int fc_flush(flash_cache_line_t *fl)
|
||||
{
|
||||
size_t bytes = (fl->index + 1) * sizeof(fl->words[0]);
|
||||
size_t rv = up_progmem_write(fl->start_address, fl->words, bytes);
|
||||
|
||||
if (rv == bytes) {
|
||||
rv = 0;
|
||||
}
|
||||
|
||||
return rv;
|
||||
}
|
||||
|
||||
int fc_write(uint32_t address, uint32_t word)
|
||||
{
|
||||
flash_cache_line_t *fc = fc_line_select(address);
|
||||
flash_cache_line_t *fc1 = &flash_cache[1];
|
||||
uint32_t index = FC_ADDR2INDX(address);
|
||||
int rv = 0;
|
||||
|
||||
if (fc == NULL && index == 0) {
|
||||
fc = fc1;
|
||||
fc->start_address = address;
|
||||
}
|
||||
|
||||
if (fc) {
|
||||
|
||||
fc->words[index] = word;
|
||||
|
||||
// Are we back writing the first word?
|
||||
|
||||
if (fc == &flash_cache[0] && index == 0 && fc->index == 7) {
|
||||
|
||||
if (fc_is_dirty(fc1)) {
|
||||
|
||||
// write out last fragment of data
|
||||
|
||||
rv = fc_flush(fc1);
|
||||
|
||||
if (rv != 0) {
|
||||
fcl_reset(fc1);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
rv = fc_flush(fc);
|
||||
fcl_reset(fc);
|
||||
return rv;
|
||||
}
|
||||
|
||||
fc->index = index;
|
||||
}
|
||||
|
||||
return rv;
|
||||
}
|
||||
|
||||
uint32_t fc_read(uint32_t address)
|
||||
{
|
||||
// Assume a cache miss read from FLASH memory
|
||||
|
||||
uint32_t rv = *(uint32_t *) address;
|
||||
|
||||
flash_cache_line_t *fc = fc_line_select(address);
|
||||
|
||||
if (fc) {
|
||||
|
||||
// Cache hit retrieve word from cache
|
||||
|
||||
uint32_t index = FC_ADDR2INDX(address);
|
||||
rv = fc->words[index];
|
||||
|
||||
// Reading the last word in cache (not first words)
|
||||
|
||||
if (fc != &flash_cache[0] && index == FC_LAST_WORD) {
|
||||
if (fc_flush(fc)) {
|
||||
rv ^= 0xffffffff;
|
||||
|
||||
} else {
|
||||
fcl_reset(fc);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return rv;
|
||||
}
|
|
@ -0,0 +1,69 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
|
||||
/* The modern flash controllers manage flash for ECC
|
||||
* On the H7 there is a block size (256) bits
|
||||
* This code translates between the bootloaders word read/write
|
||||
* interface and the H7 need for block based writes.
|
||||
*
|
||||
* All writes* are buffered until 8 word can be written.
|
||||
* Verification is made from the cache. On the verification of the
|
||||
* 8th word all the wordfs in the the cache are written to flash.
|
||||
* If the write fails the value returned for the last word is negated
|
||||
* to ensure an error on verification.
|
||||
*
|
||||
* *writes to the first 8 words of flash at APP_LOAD_ADDRESS
|
||||
* are buffered until the "first word" is written with the real value (not 0xffffffff)
|
||||
*
|
||||
*/
|
||||
|
||||
#define FC_NUMBER_LINES 2 // Number of cache lines.
|
||||
#define FC_NUMBER_WORDS 8 // Number of words per cache line.
|
||||
#define FC_LAST_WORD FC_NUMBER_WORDS-1 // The index of the last word in cache line.
|
||||
#define FC_ADDRESS_MASK ~(sizeof(flash_cache[0].words)-1) // Cache tag from address
|
||||
#define FC_ADDR2INDX(a) (((a) / sizeof(flash_cache[0].words[0])) % FC_NUMBER_WORDS) // index from address
|
||||
#define FC_CLEAN ((uint32_t)-1) // Cache clean
|
||||
|
||||
// Cache line
|
||||
typedef struct flash_cache_line_t {
|
||||
uint32_t index; // Index of word written
|
||||
uint32_t start_address; // cache tag (address in FLASH this is buffering)
|
||||
uint32_t words[FC_NUMBER_WORDS]; // Buffered data
|
||||
} flash_cache_line_t;
|
||||
|
||||
// Resets the cache - all lines flashed and cache_line[0] start_address == APP_LOAD_ADDRESS
|
||||
void fc_reset(void);
|
||||
// Cache operations
|
||||
uint32_t fc_read(uint32_t address);
|
||||
int fc_write(uint32_t address, uint32_t word);
|
|
@ -0,0 +1,76 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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 "up_arch.h"
|
||||
#include "systick.h"
|
||||
#include <nvic.h>
|
||||
|
||||
uint8_t systick_get_countflag(void)
|
||||
{
|
||||
return (getreg32(NVIC_SYSTICK_CTRL) & NVIC_SYSTICK_CTRL_COUNTFLAG) ? 1 : 0;
|
||||
}
|
||||
|
||||
// See 2.2.3 SysTick external clock is not HCLK/8
|
||||
uint32_t g_divisor = 1;
|
||||
void systick_set_reload(uint32_t value)
|
||||
{
|
||||
putreg32((((value * g_divisor) << NVIC_SYSTICK_RELOAD_SHIFT) & NVIC_SYSTICK_RELOAD_MASK), NVIC_SYSTICK_RELOAD);
|
||||
}
|
||||
|
||||
|
||||
void systick_set_clocksource(uint8_t clocksource)
|
||||
{
|
||||
g_divisor = (clocksource == CLKSOURCE_EXTERNAL) ? 8 : 1;
|
||||
modifyreg32(NVIC_SYSTICK_CTRL, NVIC_SYSTICK_CTRL_CLKSOURCE, clocksource & NVIC_SYSTICK_CTRL_CLKSOURCE);
|
||||
}
|
||||
|
||||
void systick_counter_enable(void)
|
||||
{
|
||||
modifyreg32(NVIC_SYSTICK_CTRL, 0, NVIC_SYSTICK_CTRL_ENABLE);
|
||||
}
|
||||
|
||||
void systick_counter_disable(void)
|
||||
{
|
||||
modifyreg32(NVIC_SYSTICK_CTRL, NVIC_SYSTICK_CTRL_ENABLE, 0);
|
||||
putreg32(0, NVIC_SYSTICK_CURRENT);
|
||||
}
|
||||
|
||||
void systick_interrupt_enable(void)
|
||||
{
|
||||
modifyreg32(NVIC_SYSTICK_CTRL, 0, NVIC_SYSTICK_CTRL_TICKINT);
|
||||
}
|
||||
|
||||
void systick_interrupt_disable(void)
|
||||
{
|
||||
modifyreg32(NVIC_SYSTICK_CTRL, NVIC_SYSTICK_CTRL_TICKINT, 0);
|
||||
}
|
|
@ -0,0 +1,44 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 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 CLKSOURCE_EXTERNAL 0
|
||||
#define CLKSOURCE_PROCESOR NVIC_SYSTICK_CTRL_CLKSOURCE
|
||||
|
||||
uint8_t systick_get_countflag(void);
|
||||
void systick_set_reload(uint32_t value);
|
||||
void systick_set_clocksource(uint8_t clocksource);
|
||||
void systick_counter_enable(void);
|
||||
void systick_counter_disable(void);
|
||||
void systick_interrupt_enable(void);
|
||||
void systick_interrupt_disable(void);
|
|
@ -0,0 +1,130 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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 "uart.h"
|
||||
#include <string.h>
|
||||
#include<stdio.h>
|
||||
#include<fcntl.h>
|
||||
#include<termios.h>
|
||||
//#define SERIAL_TRACE
|
||||
|
||||
int g_uart_df = -1;
|
||||
|
||||
#if defined(SERIAL_TRACE)
|
||||
int in = 0;
|
||||
int out = 0;
|
||||
char in_trace[254];
|
||||
char out_trace[254];
|
||||
#endif
|
||||
|
||||
|
||||
void uart_cinit(void *config)
|
||||
{
|
||||
char *init = strdup(config ? (char *) config : "");
|
||||
char *pt = strtok((char *) init, ",");
|
||||
char *device = "/dev/ttyS0";
|
||||
int baud = 115200;
|
||||
|
||||
if (pt != NULL) {
|
||||
device = pt;
|
||||
pt = strtok(NULL, ",");
|
||||
|
||||
if (pt != NULL) {
|
||||
baud = atol(pt);
|
||||
}
|
||||
}
|
||||
|
||||
int fd = open(device, O_RDWR | O_NONBLOCK);
|
||||
|
||||
if (fd >= 0) {
|
||||
|
||||
g_uart_df = fd;
|
||||
struct termios t;
|
||||
|
||||
tcgetattr(g_uart_df, &t);
|
||||
t.c_cflag &= ~(CSIZE | PARENB | CSTOPB);
|
||||
t.c_cflag |= (CS8);
|
||||
cfsetspeed(&t, baud);
|
||||
tcsetattr(g_uart_df, TCSANOW, &t);
|
||||
}
|
||||
|
||||
free(init);
|
||||
}
|
||||
|
||||
void uart_cfini(void)
|
||||
{
|
||||
close(g_uart_df);
|
||||
g_uart_df = -1;
|
||||
}
|
||||
int uart_cin(void)
|
||||
{
|
||||
int c = -1;
|
||||
|
||||
if (g_uart_df >= 0) {
|
||||
char b;
|
||||
|
||||
if (read(g_uart_df, &b, 1) == 1) {
|
||||
c = b;
|
||||
#if defined(SERIAL_TRACE)
|
||||
in_trace[in] = b;
|
||||
in++;
|
||||
in &= 255;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
return c;
|
||||
}
|
||||
void uart_cout(uint8_t *buf, unsigned len)
|
||||
{
|
||||
uint32_t timeout = 1000;
|
||||
|
||||
for (unsigned i = 0; i < len; i++) {
|
||||
while (timeout) {
|
||||
if (write(g_uart_df, &buf[i], 1) == 1) {
|
||||
#if defined(SERIAL_TRACE)
|
||||
out_trace[out] = buf[i];
|
||||
out++;
|
||||
out &= 255;
|
||||
#endif
|
||||
timeout = 1000;
|
||||
break;
|
||||
|
||||
} else {
|
||||
if (timeout-- == 0) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,802 @@
|
|||
/*
|
||||
* STM32F7 board support for the bootloader.
|
||||
*
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
|
||||
#include "hw_config.h"
|
||||
|
||||
#include <stm32_pwr.h>
|
||||
#include <stm32_rtc.h>
|
||||
#include <stm32_rcc.h>
|
||||
#include <nvic.h>
|
||||
#include <nuttx/progmem.h>
|
||||
#include <lib/systick.h>
|
||||
#include <lib/flash_cache.h>
|
||||
|
||||
#include "bl.h"
|
||||
#include "uart.h"
|
||||
|
||||
|
||||
#define MK_GPIO_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT))
|
||||
|
||||
#define BOOTLOADER_RESERVATION_SIZE (128 * 1024)
|
||||
|
||||
//STM DocID018909 Rev 8 Sect 38.18 and DocID026670 Rev 5 40.6.1 (MCU device ID code)
|
||||
# define REVID_MASK 0xFFFF0000
|
||||
# define DEVID_MASK 0xFFF
|
||||
|
||||
|
||||
/* magic numbers from reference manual */
|
||||
#define STM32_UNKNOWN 0
|
||||
#define STM32H74xx_75xx 0x450
|
||||
#define STM32F74xxx_75xxx 0x449
|
||||
|
||||
typedef enum mcu_rev_e {
|
||||
MCU_REV_Z = 0x1001,
|
||||
MCU_REV_Y = 0x1003,
|
||||
MCU_REV_X = 0x2001,
|
||||
MCU_REV_V = 0x2003
|
||||
} mcu_rev_e;
|
||||
|
||||
typedef struct mcu_des_t {
|
||||
uint16_t mcuid;
|
||||
const char *desc;
|
||||
char rev;
|
||||
} mcu_des_t;
|
||||
|
||||
// The default CPU ID of STM32_UNKNOWN is 0 and is in offset 0
|
||||
// Before a rev is known it is set to ?
|
||||
// There for new silicon will result in STM32F4..,?
|
||||
mcu_des_t mcu_descriptions[] = {
|
||||
{ STM32_UNKNOWN, "STM32???????", '?'},
|
||||
{ STM32H74xx_75xx, "STM32H7[4|5]x", '?'},
|
||||
};
|
||||
|
||||
typedef struct mcu_rev_t {
|
||||
mcu_rev_e revid;
|
||||
char rev;
|
||||
} mcu_rev_t;
|
||||
|
||||
/*
|
||||
* This table is used to look look up the revision
|
||||
* of a given chip.
|
||||
*/
|
||||
const mcu_rev_t silicon_revs[] = {
|
||||
{MCU_REV_Y, 'Y'}, /* Revision Y */
|
||||
{MCU_REV_X, 'X'}, /* Revision X */
|
||||
{MCU_REV_V, 'V'}, /* Revision V */
|
||||
{MCU_REV_Z, 'Z'}, /* Revision Z */
|
||||
};
|
||||
|
||||
#define APP_SIZE_MAX (BOARD_FLASH_SIZE - (BOOTLOADER_RESERVATION_SIZE + APP_RESERVATION_SIZE))
|
||||
|
||||
|
||||
/* context passed to cinit */
|
||||
#if INTERFACE_USART
|
||||
# define BOARD_INTERFACE_CONFIG_USART INTERFACE_USART_CONFIG
|
||||
#endif
|
||||
#if INTERFACE_USB
|
||||
# define BOARD_INTERFACE_CONFIG_USB INTERFACE_USB_CONFIG
|
||||
#endif
|
||||
|
||||
/* board definition */
|
||||
struct boardinfo board_info = {
|
||||
.board_type = BOARD_TYPE,
|
||||
.board_rev = 0,
|
||||
.fw_size = 0,
|
||||
.systick_mhz = 416,
|
||||
};
|
||||
|
||||
static void board_init(void);
|
||||
|
||||
#define BOOT_RTC_SIGNATURE 0xb007b007
|
||||
#define BOOT_RTC_REG MMIO32(RTC_BASE + 0x50)
|
||||
|
||||
/* State of an inserted USB cable */
|
||||
static bool usb_connected = false;
|
||||
|
||||
static uint32_t board_get_rtc_signature(void)
|
||||
{
|
||||
/* enable the backup registers */
|
||||
stm32_pwr_initbkp(true);
|
||||
|
||||
uint32_t result = getreg32(STM32_RTC_BK0R);
|
||||
|
||||
/* disable the backup registers */
|
||||
stm32_pwr_initbkp(false);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
static void
|
||||
board_set_rtc_signature(uint32_t sig)
|
||||
{
|
||||
/* enable the backup registers */
|
||||
stm32_pwr_initbkp(true);
|
||||
|
||||
putreg32(sig, STM32_RTC_BK0R);
|
||||
|
||||
/* disable the backup registers */
|
||||
stm32_pwr_initbkp(false);
|
||||
|
||||
}
|
||||
|
||||
static bool board_test_force_pin(void)
|
||||
{
|
||||
#if defined(BOARD_FORCE_BL_PIN_IN) && defined(BOARD_FORCE_BL_PIN_OUT)
|
||||
/* two pins strapped together */
|
||||
volatile unsigned samples = 0;
|
||||
volatile unsigned vote = 0;
|
||||
|
||||
for (volatile unsigned cycles = 0; cycles < 10; cycles++) {
|
||||
px4_arch_gpiowrite(BOARD_FORCE_BL_PIN_OUT, 1);
|
||||
|
||||
for (unsigned count = 0; count < 20; count++) {
|
||||
if (px4_arch_gpioread(BOARD_FORCE_BL_PIN_IN) != 0) {
|
||||
vote++;
|
||||
}
|
||||
|
||||
samples++;
|
||||
}
|
||||
|
||||
px4_arch_gpiowrite(BOARD_FORCE_BL_PIN_OUT, 0);
|
||||
|
||||
for (unsigned count = 0; count < 20; count++) {
|
||||
if (px4_arch_gpioread(BOARD_FORCE_BL_PIN_IN) == 0) {
|
||||
vote++;
|
||||
}
|
||||
|
||||
samples++;
|
||||
}
|
||||
}
|
||||
|
||||
/* the idea here is to reject wire-to-wire coupling, so require > 90% agreement */
|
||||
if ((vote * 100) > (samples * 90)) {
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(BOARD_FORCE_BL_PIN)
|
||||
/* single pin pulled up or down */
|
||||
volatile unsigned samples = 0;
|
||||
volatile unsigned vote = 0;
|
||||
|
||||
for (samples = 0; samples < 200; samples++) {
|
||||
if ((px4_arch_gpioread(BOARD_FORCE_BL_PIN) ? 1 : 0) == BOARD_FORCE_BL_STATE) {
|
||||
vote++;
|
||||
}
|
||||
}
|
||||
|
||||
/* reject a little noise */
|
||||
if ((vote * 100) > (samples * 90)) {
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
#if INTERFACE_USART
|
||||
static bool board_test_usart_receiving_break(void)
|
||||
{
|
||||
#if !defined(SERIAL_BREAK_DETECT_DISABLED)
|
||||
/* (re)start the SysTick timer system */
|
||||
systick_interrupt_disable(); // Kill the interrupt if it is still active
|
||||
systick_counter_disable(); // Stop the timer
|
||||
systick_set_clocksource(CLKSOURCE_PROCESOR);
|
||||
|
||||
/* Set the timer period to be half the bit rate
|
||||
*
|
||||
* Baud rate = 115200, therefore bit period = 8.68us
|
||||
* Half the bit rate = 4.34us
|
||||
* Set period to 4.34 microseconds (timer_period = timer_tick / timer_reset_frequency = 168MHz / (1/4.34us) = 729.12 ~= 729)
|
||||
*/
|
||||
systick_set_reload(729); /* 4.3us tick, magic number */
|
||||
systick_counter_enable(); // Start the timer
|
||||
|
||||
uint8_t cnt_consecutive_low = 0;
|
||||
uint8_t cnt = 0;
|
||||
|
||||
/* Loop for 3 transmission byte cycles and count the low and high bits. Sampled at a rate to be able to count each bit twice.
|
||||
*
|
||||
* One transmission byte is 10 bits (8 bytes of data + 1 start bit + 1 stop bit)
|
||||
* We sample at every half bit time, therefore 20 samples per transmission byte,
|
||||
* therefore 60 samples for 3 transmission bytes
|
||||
*/
|
||||
while (cnt < 60) {
|
||||
// Only read pin when SysTick timer is true
|
||||
if (systick_get_countflag() == 1) {
|
||||
if (gpio_get(BOARD_PORT_USART_RX, BOARD_PIN_RX) == 0) {
|
||||
cnt_consecutive_low++; // Increment the consecutive low counter
|
||||
|
||||
} else {
|
||||
cnt_consecutive_low = 0; // Reset the consecutive low counter
|
||||
}
|
||||
|
||||
cnt++;
|
||||
}
|
||||
|
||||
// If 9 consecutive low bits were received break out of the loop
|
||||
if (cnt_consecutive_low >= 18) {
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
systick_counter_disable(); // Stop the timer
|
||||
|
||||
/*
|
||||
* If a break is detected, return true, else false
|
||||
*
|
||||
* Break is detected if line was low for 9 consecutive bits.
|
||||
*/
|
||||
if (cnt_consecutive_low >= 18) {
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // !defined(SERIAL_BREAK_DETECT_DISABLED)
|
||||
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
uint32_t
|
||||
board_get_devices(void)
|
||||
{
|
||||
uint32_t devices = BOOT_DEVICES_SELECTION;
|
||||
|
||||
if (usb_connected) {
|
||||
devices &= BOOT_DEVICES_FILTER_ONUSB;
|
||||
}
|
||||
|
||||
return devices;
|
||||
}
|
||||
|
||||
static void
|
||||
board_init(void)
|
||||
{
|
||||
/* fix up the max firmware size, we have to read memory to get this */
|
||||
board_info.fw_size = APP_SIZE_MAX;
|
||||
|
||||
#if defined(BOARD_POWER_PIN_OUT)
|
||||
/* Configure the Power pins */
|
||||
px4_arch_configgpio(BOARD_POWER_PIN_OUT);
|
||||
px4_arch_gpiowrite(BOARD_POWER_PIN_OUT, BOARD_POWER_ON);
|
||||
#endif
|
||||
|
||||
#if INTERFACE_USB
|
||||
#if !defined(BOARD_USB_VBUS_SENSE_DISABLED)
|
||||
/* enable configured GPIO to sample VBUS */
|
||||
# if defined(USE_VBUS_PULL_DOWN)
|
||||
px4_arch_configgpio((GPIO_OTGFS_VBUS & GPIO_PUPD_MASK) | GPIO_PULLDOWN);
|
||||
# else
|
||||
px4_arch_configgpio((GPIO_OTGFS_VBUS & GPIO_PUPD_MASK) | GPIO_FLOAT);
|
||||
# endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if INTERFACE_USART
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_FORCE_BL_PIN_IN) && defined(BOARD_FORCE_BL_PIN_OUT)
|
||||
/* configure the force BL pins */
|
||||
px4_arch_configgpio(BOARD_FORCE_BL_PIN_IN);
|
||||
px4_arch_configgpio(BOARD_FORCE_BL_PIN_OUT);
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_FORCE_BL_PIN)
|
||||
/* configure the force BL pins */
|
||||
px4_arch_configgpio(BOARD_FORCE_BL_PIN);
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_PIN_LED_ACTIVITY)
|
||||
/* Initialize LEDs */
|
||||
px4_arch_configgpio(BOARD_PIN_LED_ACTIVITY);
|
||||
#endif
|
||||
#if defined(BOARD_PIN_LED_BOOTLOADER)
|
||||
/* Initialize LEDs */
|
||||
px4_arch_configgpio(BOARD_PIN_LED_BOOTLOADER);
|
||||
#endif
|
||||
}
|
||||
|
||||
void
|
||||
board_deinit(void)
|
||||
{
|
||||
|
||||
#if INTERFACE_USART
|
||||
#endif
|
||||
|
||||
#if INTERFACE_USB
|
||||
px4_arch_configgpio(MK_GPIO_INPUT(GPIO_OTGFS_VBUS));
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_FORCE_BL_PIN_IN) && defined(BOARD_FORCE_BL_PIN_OUT)
|
||||
/* deinitialise the force BL pins */
|
||||
px4_arch_configgpio(MK_GPIO_INPUT(BOARD_FORCE_BL_PIN_IN));
|
||||
px4_arch_configgpio(MK_GPIO_INPUT(BOARD_FORCE_BL_PIN_OUT));
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_FORCE_BL_PIN)
|
||||
/* deinitialise the force BL pin */
|
||||
px4_arch_configgpio(MK_GPIO_INPUT(BOARD_FORCE_BL_PIN));
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_POWER_PIN_OUT) && defined(BOARD_POWER_PIN_RELEASE)
|
||||
/* deinitialize the POWER pin - with the assumption the hold up time of
|
||||
* the voltage being bleed off by an inupt pin impedance will allow
|
||||
* enough time to boot the app
|
||||
*/
|
||||
px4_arch_configgpio(MK_GPIO_INPUT(BOARD_POWER_PIN_OUT));
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_PIN_LED_ACTIVITY)
|
||||
/* Initialize LEDs */
|
||||
px4_arch_configgpio(MK_GPIO_INPUT(BOARD_PIN_LED_ACTIVITY));
|
||||
#endif
|
||||
#if defined(BOARD_PIN_LED_BOOTLOADER)
|
||||
/* Initialize LEDs */
|
||||
px4_arch_configgpio(MK_GPIO_INPUT(BOARD_PIN_LED_BOOTLOADER));
|
||||
#endif
|
||||
|
||||
|
||||
/* disable the AHB peripheral clocks */
|
||||
putreg32(0, STM32_RCC_AHB1ENR);
|
||||
}
|
||||
|
||||
inline void arch_systic_init(void)
|
||||
{
|
||||
/* (re)start the timer system */
|
||||
systick_set_clocksource(CLKSOURCE_PROCESOR);
|
||||
systick_set_reload(board_info.systick_mhz * 1000); /* 1ms tick, magic number */
|
||||
systick_interrupt_enable();
|
||||
systick_counter_enable();
|
||||
}
|
||||
|
||||
inline void arch_systic_deinit(void)
|
||||
{
|
||||
/* kill the systick interrupt */
|
||||
systick_interrupt_disable();
|
||||
systick_counter_disable();
|
||||
systick_set_clocksource(CLKSOURCE_EXTERNAL);
|
||||
systick_set_reload(0); /* 1ms tick, magic number */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the RCC clock configuration.
|
||||
*
|
||||
* @param clock_setup : The clock configuration to set
|
||||
*/
|
||||
static inline void
|
||||
clock_init(void)
|
||||
{
|
||||
// Done by Nuttx
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Resets the RCC clock configuration to the default reset state.
|
||||
* @note The default reset state of the clock configuration is given below:
|
||||
* - HSI ON and used as system clock source
|
||||
* - HSE, PLL and PLLI2S OFF
|
||||
* - AHB, APB1 and APB2 prescaler set to 1.
|
||||
* - CSS, MCO1 and MCO2 OFF
|
||||
* - All interrupts disabled
|
||||
* @note This function doesn't modify the configuration of the
|
||||
* - Peripheral clocks
|
||||
* - LSI, LSE and RTC clocks
|
||||
*/
|
||||
void
|
||||
clock_deinit(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
|
||||
/* Enable internal high-speed oscillator. */
|
||||
|
||||
regval = getreg32(STM32_RCC_CR);
|
||||
regval |= RCC_CR_HSION;
|
||||
putreg32(regval, STM32_RCC_CR);
|
||||
|
||||
/* Check if the HSIRDY flag is the set in the CR */
|
||||
|
||||
while ((getreg32(STM32_RCC_CR) & RCC_CR_HSIRDY) == 0);
|
||||
|
||||
/* Reset the RCC_CFGR register */
|
||||
putreg32(0, STM32_RCC_CFGR);
|
||||
|
||||
/* Stop the HSE, CSS, PLL, PLLI2S, PLLSAI */
|
||||
regval = getreg32(STM32_RCC_CR);
|
||||
regval &= ~(RCC_CR_HSEON | RCC_CR_PLL1ON | RCC_CR_PLL2ON | RCC_CR_PLL3ON | RCC_CR_CSSHSEON);
|
||||
putreg32(regval, STM32_RCC_CR);
|
||||
|
||||
/* Reset the RCC_PLLCFGR register */
|
||||
putreg32(0x01FF0000, STM32_RCC_PLLCFGR);
|
||||
|
||||
/* Reset the HSEBYP bit */
|
||||
regval = getreg32(STM32_RCC_CR);
|
||||
regval &= ~(RCC_CR_HSEBYP);
|
||||
putreg32(regval, STM32_RCC_CR);
|
||||
|
||||
}
|
||||
|
||||
inline void arch_flash_lock(void)
|
||||
{
|
||||
stm32h7_flash_lock(STM32_FLASH_BANK1);
|
||||
stm32h7_flash_lock(STM32_FLASH_BANK2);
|
||||
}
|
||||
|
||||
inline void arch_flash_unlock(void)
|
||||
{
|
||||
fc_reset();
|
||||
stm32h7_flash_unlock(STM32_FLASH_BANK1);
|
||||
stm32h7_flash_unlock(STM32_FLASH_BANK2);
|
||||
}
|
||||
|
||||
inline void arch_setvtor(uint32_t address)
|
||||
{
|
||||
putreg32(address, NVIC_VECTAB);
|
||||
}
|
||||
|
||||
uint32_t
|
||||
flash_func_sector_size(unsigned sector)
|
||||
{
|
||||
if (sector <= BOARD_FLASH_SECTORS) {
|
||||
return 128 * 1024;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
flash_func_erase_sector(unsigned sector)
|
||||
{
|
||||
if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* blank-check the sector */
|
||||
|
||||
bool blank = up_progmem_ispageerased(sector) == 0;
|
||||
|
||||
/* erase the sector if it failed the blank check */
|
||||
if (!blank) {
|
||||
up_progmem_eraseblock(sector);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
flash_func_write_word(uint32_t address, uint32_t word)
|
||||
{
|
||||
address += APP_LOAD_ADDRESS;
|
||||
fc_write(address, word);
|
||||
}
|
||||
|
||||
uint32_t flash_func_read_word(uint32_t address)
|
||||
{
|
||||
|
||||
if (address & 3) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return fc_read(address + APP_LOAD_ADDRESS);
|
||||
|
||||
}
|
||||
|
||||
|
||||
uint32_t
|
||||
flash_func_read_otp(uint32_t address)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint32_t get_mcu_id(void)
|
||||
{
|
||||
return *(uint32_t *)STM32_DEBUGMCU_BASE;
|
||||
}
|
||||
|
||||
int get_mcu_desc(int max, uint8_t *revstr)
|
||||
{
|
||||
uint32_t idcode = (*(uint32_t *) STM32_DEBUGMCU_BASE);
|
||||
int32_t mcuid = idcode & DEVID_MASK;
|
||||
mcu_rev_e revid = (idcode & REVID_MASK) >> 16;
|
||||
|
||||
mcu_des_t des = mcu_descriptions[STM32_UNKNOWN];
|
||||
|
||||
for (unsigned int i = 0; i < arraySize(mcu_descriptions); i++) {
|
||||
if (mcuid == mcu_descriptions[i].mcuid) {
|
||||
des = mcu_descriptions[i];
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
for (unsigned int i = 0; i < arraySize(silicon_revs); i++) {
|
||||
if (silicon_revs[i].revid == revid) {
|
||||
des.rev = silicon_revs[i].rev;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t *endp = &revstr[max - 1];
|
||||
uint8_t *strp = revstr;
|
||||
|
||||
while (strp < endp && *des.desc) {
|
||||
*strp++ = *des.desc++;
|
||||
}
|
||||
|
||||
if (strp < endp) {
|
||||
*strp++ = ',';
|
||||
}
|
||||
|
||||
if (strp < endp) {
|
||||
*strp++ = des.rev;
|
||||
}
|
||||
|
||||
return strp - revstr;
|
||||
}
|
||||
|
||||
|
||||
int check_silicon(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint32_t
|
||||
flash_func_read_sn(uint32_t address)
|
||||
{
|
||||
// read a byte out from unique chip ID area
|
||||
// it's 12 bytes, or 3 words.
|
||||
return *(uint32_t *)(address + STM32_SYSMEM_UID);
|
||||
}
|
||||
|
||||
void
|
||||
led_on(unsigned led)
|
||||
{
|
||||
switch (led) {
|
||||
case LED_ACTIVITY:
|
||||
#if defined(BOARD_PIN_LED_ACTIVITY)
|
||||
px4_arch_gpiowrite(BOARD_PIN_LED_ACTIVITY, BOARD_LED_ON);
|
||||
#endif
|
||||
break;
|
||||
|
||||
case LED_BOOTLOADER:
|
||||
#if defined(BOARD_PIN_LED_BOOTLOADER)
|
||||
px4_arch_gpiowrite(BOARD_PIN_LED_BOOTLOADER, BOARD_LED_ON);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
led_off(unsigned led)
|
||||
{
|
||||
switch (led) {
|
||||
case LED_ACTIVITY:
|
||||
#if defined(BOARD_PIN_LED_ACTIVITY)
|
||||
px4_arch_gpiowrite(BOARD_PIN_LED_ACTIVITY, BOARD_LED_OFF);
|
||||
#endif
|
||||
break;
|
||||
|
||||
case LED_BOOTLOADER:
|
||||
#if defined(BOARD_PIN_LED_BOOTLOADER)
|
||||
px4_arch_gpiowrite(BOARD_PIN_LED_BOOTLOADER, BOARD_LED_OFF);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
led_toggle(unsigned led)
|
||||
{
|
||||
switch (led) {
|
||||
case LED_ACTIVITY:
|
||||
#if defined(BOARD_PIN_LED_ACTIVITY)
|
||||
px4_arch_gpiowrite(BOARD_PIN_LED_ACTIVITY, px4_arch_gpioread(BOARD_PIN_LED_ACTIVITY) ^ 1);
|
||||
#endif
|
||||
break;
|
||||
|
||||
case LED_BOOTLOADER:
|
||||
#if defined(BOARD_PIN_LED_BOOTLOADER)
|
||||
px4_arch_gpiowrite(BOARD_PIN_LED_BOOTLOADER, px4_arch_gpioread(BOARD_PIN_LED_BOOTLOADER) ^ 1);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/* we should know this, but we don't */
|
||||
#ifndef SCB_CPACR
|
||||
# define SCB_CPACR (*((volatile uint32_t *) (((0xE000E000UL) + 0x0D00UL) + 0x088)))
|
||||
#endif
|
||||
|
||||
int
|
||||
bootloader_main(void)
|
||||
{
|
||||
bool try_boot = true; /* try booting before we drop to the bootloader */
|
||||
unsigned timeout = BOOTLOADER_DELAY; /* if nonzero, drop out of the bootloader after this time */
|
||||
|
||||
/* Enable the FPU before we hit any FP instructions */
|
||||
SCB_CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); /* set CP10 Full Access and set CP11 Full Access */
|
||||
|
||||
#if defined(BOARD_POWER_PIN_OUT)
|
||||
|
||||
/* Here we check for the app setting the POWER_DOWN_RTC_SIGNATURE
|
||||
* in this case, we reset the signature and wait to die
|
||||
*/
|
||||
if (board_get_rtc_signature() == POWER_DOWN_RTC_SIGNATURE) {
|
||||
board_set_rtc_signature(0);
|
||||
|
||||
while (1);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* do board-specific initialisation */
|
||||
board_init();
|
||||
|
||||
/* configure the clock for bootloader activity */
|
||||
clock_init();
|
||||
|
||||
/*
|
||||
* Check the force-bootloader register; if we find the signature there, don't
|
||||
* try booting.
|
||||
*/
|
||||
if (board_get_rtc_signature() == BOOT_RTC_SIGNATURE) {
|
||||
|
||||
/*
|
||||
* Don't even try to boot before dropping to the bootloader.
|
||||
*/
|
||||
try_boot = false;
|
||||
|
||||
/*
|
||||
* Don't drop out of the bootloader until something has been uploaded.
|
||||
*/
|
||||
timeout = 0;
|
||||
|
||||
/*
|
||||
* Clear the signature so that if someone resets us while we're
|
||||
* in the bootloader we'll try to boot next time.
|
||||
*/
|
||||
board_set_rtc_signature(0);
|
||||
}
|
||||
|
||||
#ifdef BOOT_DELAY_ADDRESS
|
||||
{
|
||||
/*
|
||||
if a boot delay signature is present then delay the boot
|
||||
by at least that amount of time in seconds. This allows
|
||||
for an opportunity for a companion computer to load a
|
||||
new firmware, while still booting fast by sending a BOOT
|
||||
command
|
||||
*/
|
||||
uint32_t sig1 = flash_func_read_word(BOOT_DELAY_ADDRESS);
|
||||
uint32_t sig2 = flash_func_read_word(BOOT_DELAY_ADDRESS + 4);
|
||||
|
||||
if (sig2 == BOOT_DELAY_SIGNATURE2 &&
|
||||
(sig1 & 0xFFFFFF00) == (BOOT_DELAY_SIGNATURE1 & 0xFFFFFF00)) {
|
||||
unsigned boot_delay = sig1 & 0xFF;
|
||||
|
||||
if (boot_delay <= BOOT_DELAY_MAX) {
|
||||
try_boot = false;
|
||||
|
||||
if (timeout < boot_delay * 1000) {
|
||||
timeout = boot_delay * 1000;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Check if the force-bootloader pins are strapped; if strapped,
|
||||
* don't try booting.
|
||||
*/
|
||||
if (board_test_force_pin()) {
|
||||
try_boot = false;
|
||||
}
|
||||
|
||||
#if INTERFACE_USB
|
||||
|
||||
/*
|
||||
* Check for USB connection - if present, don't try to boot, but set a timeout after
|
||||
* which we will fall out of the bootloader.
|
||||
*
|
||||
* If the force-bootloader pins are tied, we will stay here until they are removed and
|
||||
* we then time out.
|
||||
*/
|
||||
#if defined(BOARD_VBUS)
|
||||
|
||||
if (px4_arch_gpioread(BOARD_VBUS) != 0) {
|
||||
usb_connected = true;
|
||||
/* don't try booting before we set up the bootloader */
|
||||
try_boot = false;
|
||||
}
|
||||
|
||||
#else
|
||||
try_boot = false;
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if INTERFACE_USART
|
||||
|
||||
/*
|
||||
* Check for if the USART port RX line is receiving a break command, or is being held low. If yes,
|
||||
* don't try to boot, but set a timeout after
|
||||
* which we will fall out of the bootloader.
|
||||
*
|
||||
* If the force-bootloader pins are tied, we will stay here until they are removed and
|
||||
* we then time out.
|
||||
*/
|
||||
if (board_test_usart_receiving_break()) {
|
||||
try_boot = false;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* Try to boot the app if we think we should just go straight there */
|
||||
if (try_boot) {
|
||||
|
||||
/* set the boot-to-bootloader flag so that if boot fails on reset we will stop here */
|
||||
#ifdef BOARD_BOOT_FAIL_DETECT
|
||||
board_set_rtc_signature(BOOT_RTC_SIGNATURE);
|
||||
#endif
|
||||
|
||||
/* try to boot immediately */
|
||||
jump_to_app();
|
||||
|
||||
// If it failed to boot, reset the boot signature and stay in bootloader
|
||||
board_set_rtc_signature(BOOT_RTC_SIGNATURE);
|
||||
|
||||
/* booting failed, stay in the bootloader forever */
|
||||
timeout = 0;
|
||||
}
|
||||
|
||||
|
||||
/* start the interface */
|
||||
#if INTERFACE_USART
|
||||
cinit(BOARD_INTERFACE_CONFIG_USART, USART);
|
||||
#endif
|
||||
#if INTERFACE_USB
|
||||
cinit(BOARD_INTERFACE_CONFIG_USB, USB);
|
||||
#endif
|
||||
|
||||
|
||||
#if 0
|
||||
// MCO1/02
|
||||
gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO8);
|
||||
gpio_set_output_options(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_100MHZ, GPIO8);
|
||||
gpio_set_af(GPIOA, GPIO_AF0, GPIO8);
|
||||
gpio_mode_setup(GPIOC, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO9);
|
||||
gpio_set_af(GPIOC, GPIO_AF0, GPIO9);
|
||||
#endif
|
||||
|
||||
|
||||
while (1) {
|
||||
/* run the bootloader, come back after an app is uploaded or we time out */
|
||||
bootloader(timeout);
|
||||
|
||||
/* if the force-bootloader pins are strapped, just loop back */
|
||||
if (board_test_force_pin()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
#if INTERFACE_USART
|
||||
|
||||
/* if the USART port RX line is still receiving a break, just loop back */
|
||||
if (board_test_usart_receiving_break()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* set the boot-to-bootloader flag so that if boot fails on reset we will stop here */
|
||||
#ifdef BOARD_BOOT_FAIL_DETECT
|
||||
board_set_rtc_signature(BOOT_RTC_SIGNATURE);
|
||||
#endif
|
||||
|
||||
/* look to see if we can boot the app */
|
||||
jump_to_app();
|
||||
|
||||
/* launching the app failed - stay in the bootloader forever */
|
||||
timeout = 0;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,45 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2014 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 uart.h
|
||||
*
|
||||
* UART bootloader definitions.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
extern void uart_cinit(void *config);
|
||||
extern void uart_cfini(void);
|
||||
extern int uart_cin(void);
|
||||
extern void uart_cout(uint8_t *buf, unsigned len);
|
Loading…
Reference in New Issue