synchronized up to the mcu-tool/mcuboot 4eca54f417

Synchronized to:
4eca54f417

- added precise check of the image size
- loader: Added post copy hook to swap function
- added Kconfig option for setting swap using move as default swap algorithm
- zephyr: fixed ram loading for ARM, with correct handling of vector table when code has moved to RAM.

- imgtool: add option to export public PEM

merged using GitHub web gui.

Signed-off-by: Andrzej Puzdrowski <andrzej.puzdrowski@nordicsemi.no>
This commit is contained in:
Andrzej Puzdrowski 2022-10-07 11:33:49 +02:00 committed by GitHub
commit cfec947e0f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
37 changed files with 761 additions and 66 deletions

View File

@ -21,6 +21,7 @@
#include <inttypes.h>
#include <ctype.h>
#include <stdio.h>
#include <errno.h>
#include "sysflash/sysflash.h"
@ -32,6 +33,7 @@
#include <zephyr/sys/byteorder.h>
#include <zephyr/sys/__assert.h>
#include <zephyr/drivers/flash.h>
#include <zephyr/kernel.h>
#include <zephyr/sys/crc.h>
#include <zephyr/sys/base64.h>
#include <hal/hal_flash.h>

View File

@ -387,3 +387,27 @@ boot_write_enc_key(const struct flash_area *fap, uint8_t slot,
return 0;
}
#endif
uint32_t bootutil_max_image_size(const struct flash_area *fap)
{
#if defined(MCUBOOT_SWAP_USING_SCRATCH)
return boot_status_off(fap);
#elif defined(MCUBOOT_SWAP_USING_MOVE)
struct flash_sector sector;
/* get the last sector offset */
int rc = flash_area_sector_from_off(boot_status_off(fap), &sector);
if (rc) {
BOOT_LOG_ERR("Unable to determine flash sector of the image trailer");
return 0; /* Returning of zero here should cause any check which uses
* this value to fail.
*/
}
return flash_sector_get_off(&sector);
#elif defined(MCUBOOT_OVERWRITE_ONLY)
return boot_swap_info_off(fap);
#elif defined(MCUBOOT_DIRECT_XIP)
return boot_swap_info_off(fap);
#elif defined(MCUBOOT_RAM_LOAD)
return boot_swap_info_off(fap);
#endif
}

View File

@ -463,6 +463,8 @@ struct bootsim_ram_info *bootsim_get_ram_info(void);
(flash_area_read((fap), (start), (output), (size)))
#endif /* MCUBOOT_RAM_LOAD */
uint32_t bootutil_max_image_size(const struct flash_area *fap);
#ifdef __cplusplus
}
#endif

View File

@ -268,7 +268,6 @@ bootutil_find_key(uint8_t image_index, uint8_t *key, uint16_t key_len)
#endif /* !MCUBOOT_HW_KEY */
#endif
#ifdef MCUBOOT_HW_ROLLBACK_PROT
/**
* Reads the value of an image's security counter.
*
@ -328,7 +327,6 @@ bootutil_get_img_security_cnt(struct image_header *hdr,
return 0;
}
#endif /* MCUBOOT_HW_ROLLBACK_PROT */
/*
* Verify the integrity of the image.
@ -378,6 +376,11 @@ bootutil_img_validate(struct enc_key_data *enc_state, int image_index,
goto out;
}
if (it.tlv_end > bootutil_max_image_size(fap)) {
rc = -1;
goto out;
}
/*
* Traverse through all of the TLVs, performing any checks we know
* and are able to do.

View File

@ -616,7 +616,7 @@ boot_check_header_erased(struct boot_loader_state *state, int slot)
#if (BOOT_IMAGE_NUMBER > 1) || \
defined(MCUBOOT_DIRECT_XIP) || \
defined(MCUBOOT_RAM_LOAD) || \
(defined(MCUBOOT_OVERWRITE_ONLY) && defined(MCUBOOT_DOWNGRADE_PREVENTION))
defined(MCUBOOT_DOWNGRADE_PREVENTION)
/**
* Compare image version numbers not including the build number
*
@ -1332,6 +1332,8 @@ boot_swap_image(struct boot_loader_state *state, struct boot_status *bs)
boot_status_fails);
}
#endif
rc = BOOT_HOOK_CALL(boot_copy_region_post_hook, 0, BOOT_CURR_IMG(state),
BOOT_IMG_AREA(state, BOOT_PRIMARY_SLOT), size);
return 0;
}
@ -1903,6 +1905,60 @@ boot_update_hw_rollback_protection(struct boot_loader_state *state)
#endif
}
/**
* Checks test swap downgrade prevention conditions.
*
* Function called only for swap upgrades test run. It may prevent
* swap if slot 1 image has <= version number or < security counter
*
* @param state Boot loader status information.
*
* @return 0 - image can be swapped, -1 downgrade prevention
*/
static int
check_downgrade_prevention(struct boot_loader_state *state)
{
#if defined(MCUBOOT_DOWNGRADE_PREVENTION) && \
(defined(MCUBOOT_SWAP_USING_MOVE) || defined(MCUBOOT_SWAP_USING_SCRATCH))
uint32_t security_counter[2];
int rc;
if (MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER) {
/* If there was security no counter in slot 0, allow swap */
rc = bootutil_get_img_security_cnt(&(BOOT_IMG(state, 0).hdr),
BOOT_IMG(state, 0).area,
&security_counter[0]);
if (rc != 0) {
return 0;
}
/* If there is no security counter in slot 1, or it's lower than
* that of slot 0, prevent downgrade */
rc = bootutil_get_img_security_cnt(&(BOOT_IMG(state, 1).hdr),
BOOT_IMG(state, 1).area,
&security_counter[1]);
if (rc != 0 || security_counter[0] > security_counter[1]) {
rc = -1;
}
}
else {
rc = boot_version_cmp(&boot_img_hdr(state, BOOT_SECONDARY_SLOT)->ih_ver,
&boot_img_hdr(state, BOOT_PRIMARY_SLOT)->ih_ver);
}
if (rc < 0) {
/* Image in slot 0 prevents downgrade, delete image in slot 1 */
BOOT_LOG_INF("Image in slot 1 erased due to downgrade prevention");
flash_area_erase(BOOT_IMG(state, 1).area, 0,
flash_area_get_size(BOOT_IMG(state, 1).area));
} else {
rc = 0;
}
return rc;
#else
(void)state;
return 0;
#endif
}
fih_int
context_boot_go(struct boot_loader_state *state, struct boot_rsp *rsp)
{
@ -2031,7 +2087,13 @@ context_boot_go(struct boot_loader_state *state, struct boot_rsp *rsp)
case BOOT_SWAP_TYPE_NONE:
break;
case BOOT_SWAP_TYPE_TEST: /* fallthrough */
case BOOT_SWAP_TYPE_TEST:
if (check_downgrade_prevention(state) != 0) {
/* Downgrade prevented */
BOOT_SWAP_TYPE(state) = BOOT_SWAP_TYPE_NONE;
break;
}
/* fallthrough */
case BOOT_SWAP_TYPE_PERM: /* fallthrough */
case BOOT_SWAP_TYPE_REVERT:
rc = BOOT_HOOK_CALL(boot_perform_update_hook, BOOT_HOOK_REGULAR,

View File

@ -213,7 +213,6 @@ set(port_srcs
${CMAKE_CURRENT_LIST_DIR}/port/esp_mcuboot.c
${CMAKE_CURRENT_LIST_DIR}/port/esp_loader.c
${CMAKE_CURRENT_LIST_DIR}/os.c
${CMAKE_CURRENT_LIST_DIR}/serial_adapter.c
)
if(CONFIG_ESP_MCUBOOT_SERIAL)
@ -227,7 +226,7 @@ if(CONFIG_ESP_MCUBOOT_SERIAL)
${BOOT_SERIAL_DIR}/src/zcbor_common.c
)
list(APPEND port_srcs
${CMAKE_CURRENT_LIST_DIR}/serial_adapter.c
${CMAKE_CURRENT_LIST_DIR}/port/${MCUBOOT_TARGET}/serial_adapter.c
${MBEDTLS_DIR}/library/base64.c
)
list(APPEND CRYPTO_INC
@ -247,6 +246,7 @@ target_include_directories(
${APP_EXECUTABLE}
PUBLIC
${BOOTUTIL_DIR}/include
${BOOTUTIL_DIR}/src
${BOOT_SERIAL_DIR}/include
${CRYPTO_INC}
${CMAKE_CURRENT_LIST_DIR}/include

View File

@ -41,6 +41,7 @@ list(APPEND include_dirs
${esp_idf_dir}/components/efuse/${MCUBOOT_TARGET}/include
${esp_idf_dir}/components/efuse/private_include
${esp_idf_dir}/components/efuse/${MCUBOOT_TARGET}/private_include
${esp_idf_dir}/components/esp_system/include
${esp_idf_dir}/components/newlib/platform_include
)

View File

@ -143,6 +143,18 @@
#define CONFIG_MCUBOOT_SERIAL
#endif
/*
* When a serial recovery process is receiving the image data, this option
* enables it to erase flash progressively (by sectors) instead of the
* default behavior that is erasing whole image size of flash area after
* receiving first frame.
* Enabling this options prevents stalling the beginning of transfer
* for the time needed to erase large chunk of flash.
*/
#ifdef CONFIG_ESP_MCUBOOT_ERASE_PROGRESSIVELY
#define MCUBOOT_ERASE_PROGRESSIVELY
#endif
/* Serial extensions are not implemented
*/
#define MCUBOOT_PERUSER_MGMT_GROUP_ENABLED 0

View File

@ -19,6 +19,7 @@
#include "bootloader_init.h"
#include "bootloader_common.h"
#include "bootloader_console.h"
#include "bootloader_clock.h"
#include "bootloader_flash_config.h"
#include "bootloader_mem.h"
@ -31,6 +32,10 @@
#include "soc/efuse_reg.h"
#include "soc/rtc.h"
#include "hal/gpio_hal.h"
#include <hal/gpio_ll.h>
#include <hal/uart_ll.h>
#include "esp32c3/rom/cache.h"
#include "esp32c3/rom/spi_flash.h"
@ -39,6 +44,12 @@
extern esp_image_header_t WORD_ALIGNED_ATTR bootloader_image_hdr;
#if CONFIG_ESP_CONSOLE_UART_CUSTOM
static uart_dev_t *alt_console_uart_dev = (CONFIG_ESP_CONSOLE_UART_NUM == 0) ?
&UART0 :
&UART1;
#endif
void IRAM_ATTR bootloader_configure_spi_pins(int drv)
{
const uint32_t spiconfig = esp_rom_efuse_get_flash_gpio_info();
@ -161,15 +172,13 @@ static void bootloader_super_wdt_auto_feed(void)
REG_WRITE(RTC_CNTL_SWD_WPROTECT_REG, 0);
}
static void bootloader_init_uart_console(void)
#if CONFIG_ESP_CONSOLE_UART_CUSTOM
void IRAM_ATTR esp_rom_uart_putc(char c)
{
const int uart_num = 0;
esp_rom_install_uart_printf();
esp_rom_uart_tx_wait_idle(0);
uint32_t clock_hz = UART_CLK_FREQ_ROM;
esp_rom_uart_set_clock_baudrate(uart_num, clock_hz, CONFIG_ESP_CONSOLE_UART_BAUDRATE);
while (uart_ll_get_txfifo_len(alt_console_uart_dev) == 0);
uart_ll_write_txfifo(alt_console_uart_dev, (const uint8_t *) &c, 1);
}
#endif
esp_err_t bootloader_init(void)
{
@ -190,7 +199,7 @@ esp_err_t bootloader_init(void)
// config clock
bootloader_clock_configure();
/* initialize uart console, from now on, we can use ets_printf */
bootloader_init_uart_console();
bootloader_console_init();
// update flash ID
bootloader_flash_update_id();
// read bootloader header

View File

@ -77,6 +77,9 @@ uint8_t flash_area_erased_val(const struct flash_area *area);
int flash_area_get_sectors(int fa_id, uint32_t *count,
struct flash_sector *sectors);
//! Retrieve the flash sector a given offset belongs to.
int flash_area_sector_from_off(uint32_t off, struct flash_sector *sector);
//! Returns the `fa_id` for slot, where slot is 0 (primary) or 1 (secondary).
//!
//! `image_index` (0 or 1) is the index of the image. Image index is

View File

@ -15,6 +15,9 @@ CONFIG_ESP_SCRATCH_SIZE=0x40000
# Enables the MCUboot Serial Recovery, that allows the use of
# MCUMGR to upload a firmware through the serial port
# CONFIG_ESP_MCUBOOT_SERIAL=y
# Use sector erasing instead of entire image size erasing
# when uploading through Serial Recovery
# CONFIG_ESP_MCUBOOT_ERASE_PROGRESSIVELY=y
# GPIO used to boot on Serial Recovery
# CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT=32
# GPIO input type (0 for Pull-down, 1 for Pull-up)

View File

@ -40,6 +40,7 @@ SECTIONS
*libhal.a:bootloader_efuse_esp32.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_utility.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_sha.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_console.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_console_loader.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_panic.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_soc.*(.literal .text .literal.* .text.*)

View File

@ -11,9 +11,12 @@
#include <esp_rom_sys.h>
#include <soc/uart_periph.h>
#include <soc/gpio_struct.h>
#include <soc/io_mux_reg.h>
#include <soc/rtc.h>
#include <hal/gpio_types.h>
#include <hal/gpio_ll.h>
#include <hal/uart_ll.h>
#include <hal/clk_gate_ll.h>
#ifdef CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT
#define SERIAL_BOOT_GPIO_DETECT CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT
@ -88,6 +91,7 @@ int console_read(char *str, int cnt, int *newline)
read_len++;
if (read_len == cnt || str[read_len - 1] == '\n') {
stop = true;
break;
}
}
}
@ -118,10 +122,14 @@ int boot_console_init(void)
gpio_ll_output_enable(&GPIO, SERIAL_BOOT_GPIO_TX);
uart_ll_set_mode_normal(serial_boot_uart_dev);
uart_ll_set_baudrate(serial_boot_uart_dev, 115200 );
uart_ll_set_stop_bits(serial_boot_uart_dev, 1u );
uart_ll_set_parity(serial_boot_uart_dev, UART_PARITY_DISABLE );
uart_ll_set_rx_tout(serial_boot_uart_dev, 16 );
uart_ll_set_baudrate(serial_boot_uart_dev, 115200);
uart_ll_set_stop_bits(serial_boot_uart_dev, 1u);
uart_ll_set_parity(serial_boot_uart_dev, UART_PARITY_DISABLE);
uart_ll_set_rx_tout(serial_boot_uart_dev, 16);
uart_ll_set_data_bit_num(serial_boot_uart_dev, UART_DATA_8_BITS);
uart_ll_set_tx_idle_num(serial_boot_uart_dev, 0);
uart_ll_set_hw_flow_ctrl(serial_boot_uart_dev, UART_HW_FLOWCTRL_DISABLE, 100);
periph_ll_enable_clk_clear_rst(PERIPH_UART0_MODULE + SERIAL_BOOT_UART_NUM);
uart_ll_txfifo_rst(serial_boot_uart_dev);
uart_ll_rxfifo_rst(serial_boot_uart_dev);
@ -153,14 +161,14 @@ bool boot_serial_detect_pin(void)
detected = (pin_value == SERIAL_BOOT_GPIO_DETECT_VAL);
esp_rom_delay_us(50000);
if(detected) {
if(SERIAL_BOOT_DETECT_DELAY_S > 0) {
if (detected) {
if (SERIAL_BOOT_DETECT_DELAY_S > 0) {
/* The delay time is an approximation */
for(int i = 0; i < (SERIAL_BOOT_DETECT_DELAY_S * 100); i++) {
for (int i = 0; i < (SERIAL_BOOT_DETECT_DELAY_S * 100); i++) {
esp_rom_delay_us(10000);
pin_value = gpio_ll_get_level(&GPIO, SERIAL_BOOT_GPIO_DETECT);
detected = (pin_value == SERIAL_BOOT_GPIO_DETECT_VAL);
if(!detected) {
detected = (pin_value == SERIAL_BOOT_GPIO_DETECT_VAL);
if (!detected) {
break;
}
}

View File

@ -12,6 +12,41 @@ CONFIG_ESP_MCUBOOT_WDT_ENABLE=y
CONFIG_ESP_SCRATCH_OFFSET=0x210000
CONFIG_ESP_SCRATCH_SIZE=0x40000
# Enables the MCUboot Serial Recovery, that allows the use of
# MCUMGR to upload a firmware through the serial port
# CONFIG_ESP_MCUBOOT_SERIAL=y
# Use Serial through USB JTAG Serial port for Serial Recovery
# CONFIG_ESP_MCUBOOT_SERIAL_USB_SERIAL_JTAG=y
# Use sector erasing (recommended) instead of entire image size
# erasing when uploading through Serial Recovery
# CONFIG_ESP_MCUBOOT_ERASE_PROGRESSIVELY=y
# GPIO used to boot on Serial Recovery
# CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT=5
# GPIO input type (0 for Pull-down, 1 for Pull-up)
# CONFIG_ESP_SERIAL_BOOT_GPIO_INPUT_TYPE=0
# GPIO signal value
# CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT_VAL=1
# Delay time for identify the GPIO signal
# CONFIG_ESP_SERIAL_BOOT_DETECT_DELAY_S=5
# UART port used for serial communication (not needed when using USB)
# CONFIG_ESP_SERIAL_BOOT_UART_NUM=1
# GPIO for Serial RX signal
# CONFIG_ESP_SERIAL_BOOT_GPIO_RX=8
# GPIO for Serial TX signal
# CONFIG_ESP_SERIAL_BOOT_GPIO_TX=9
# Use UART0 for console printing (use either UART or USB alone)
CONFIG_ESP_CONSOLE_UART=y
CONFIG_ESP_CONSOLE_UART_NUM=0
# Configures alternative UART port for console printing
# (UART_NUM=0 must not be changed)
# CONFIG_ESP_CONSOLE_UART_CUSTOM=y
# CONFIG_ESP_CONSOLE_UART_TX_GPIO=9
# CONFIG_ESP_CONSOLE_UART_RX_GPIO=8
# Use USB JTAG Serial for console printing
# CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y
# CONFIG_ESP_SIGN_EC256=y
# CONFIG_ESP_SIGN_ED25519=n
# CONFIG_ESP_SIGN_RSA=n

View File

@ -33,13 +33,13 @@ SECTIONS
*libhal.a:bootloader_clock_loader.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_common_loader.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_init_common.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_flash.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_random.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_random*.*(.literal.bootloader_random_disable .text.bootloader_random_disable)
*libhal.a:bootloader_random*.*(.literal.bootloader_random_enable .text.bootloader_random_enable)
*libhal.a:bootloader_efuse_esp32c3.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_utility.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_sha.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_console.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_console_loader.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_panic.*(.literal .text .literal.* .text.*)
*libhal.a:bootloader_soc.*(.literal .text .literal.* .text.*)

View File

@ -0,0 +1,226 @@
/*
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <bootutil/bootutil_log.h>
#include <esp_rom_uart.h>
#include <esp_rom_gpio.h>
#include <esp_rom_sys.h>
#include <esp_rom_caps.h>
#include <soc/uart_periph.h>
#include <soc/gpio_struct.h>
#include <soc/io_mux_reg.h>
#include <soc/rtc.h>
#include <hal/gpio_types.h>
#include <hal/gpio_ll.h>
#include <hal/uart_ll.h>
#include <hal/clk_gate_ll.h>
#include <hal/usb_serial_jtag_ll.h>
#include <hal/gpio_hal.h>
#ifdef CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT
#define SERIAL_BOOT_GPIO_DETECT CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT
#else
#define SERIAL_BOOT_GPIO_DETECT GPIO_NUM_5
#endif
#ifdef CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT_VAL
#define SERIAL_BOOT_GPIO_DETECT_VAL CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT_VAL
#else
#define SERIAL_BOOT_GPIO_DETECT_VAL 1
#endif
#ifdef CONFIG_ESP_SERIAL_BOOT_DETECT_DELAY_S
#define SERIAL_BOOT_DETECT_DELAY_S CONFIG_ESP_SERIAL_BOOT_DETECT_DELAY_S
#else
#define SERIAL_BOOT_DETECT_DELAY_S 5
#endif
#ifdef CONFIG_ESP_SERIAL_BOOT_GPIO_INPUT_TYPE
#define SERIAL_BOOT_GPIO_INPUT_TYPE CONFIG_ESP_SERIAL_BOOT_GPIO_INPUT_TYPE
#else
// pull-down
#define SERIAL_BOOT_GPIO_INPUT_TYPE 0
#endif
#ifndef CONFIG_ESP_MCUBOOT_SERIAL_USB_SERIAL_JTAG
#ifdef CONFIG_ESP_SERIAL_BOOT_UART_NUM
#define SERIAL_BOOT_UART_NUM CONFIG_ESP_SERIAL_BOOT_UART_NUM
#else
#define SERIAL_BOOT_UART_NUM ESP_ROM_UART_1
#endif
#ifdef CONFIG_ESP_SERIAL_BOOT_GPIO_RX
#define SERIAL_BOOT_GPIO_RX CONFIG_ESP_SERIAL_BOOT_GPIO_RX
#else
#define SERIAL_BOOT_GPIO_RX GPIO_NUM_8
#endif
#ifdef CONFIG_ESP_SERIAL_BOOT_GPIO_TX
#define SERIAL_BOOT_GPIO_TX CONFIG_ESP_SERIAL_BOOT_GPIO_TX
#else
#define SERIAL_BOOT_GPIO_TX GPIO_NUM_9
#endif
static uart_dev_t *serial_boot_uart_dev = (SERIAL_BOOT_UART_NUM == 0) ?
&UART0 :
&UART1;
#endif
void console_write(const char *str, int cnt)
{
#ifdef CONFIG_ESP_MCUBOOT_SERIAL_USB_SERIAL_JTAG
usb_serial_jtag_ll_txfifo_flush();
while (!usb_serial_jtag_ll_txfifo_writable()) {
MCUBOOT_WATCHDOG_FEED();
}
usb_serial_jtag_ll_write_txfifo((const uint8_t *)str, cnt);
usb_serial_jtag_ll_txfifo_flush();
#else
uint32_t tx_len;
uint32_t write_len;
do {
tx_len = uart_ll_get_txfifo_len(serial_boot_uart_dev);
if (tx_len > 0) {
write_len = tx_len < cnt ? tx_len : cnt;
uart_ll_write_txfifo(serial_boot_uart_dev, (const uint8_t *)str, write_len);
cnt -= write_len;
}
MCUBOOT_WATCHDOG_FEED();
esp_rom_delay_us(1000);
} while (cnt > 0);
#endif
}
int console_read(char *str, int cnt, int *newline)
{
#ifdef CONFIG_ESP_MCUBOOT_SERIAL_USB_SERIAL_JTAG
uint32_t read_len = 0;
esp_rom_delay_us(1000);
do {
if (usb_serial_jtag_ll_rxfifo_data_available()) {
usb_serial_jtag_ll_read_rxfifo((uint8_t *)&str[read_len], 1);
read_len++;
}
MCUBOOT_WATCHDOG_FEED();
esp_rom_delay_us(1000);
} while (!(read_len == cnt || str[read_len - 1] == '\n'));
*newline = (str[read_len - 1] == '\n') ? 1 : 0;
return read_len;
#else
uint32_t len = 0;
uint32_t read_len = 0;
bool stop = false;
do {
len = uart_ll_get_rxfifo_len(serial_boot_uart_dev);
if (len > 0) {
for (uint32_t i = 0; i < len; i++) {
/* Read the character from the RX FIFO */
uart_ll_read_rxfifo(serial_boot_uart_dev, (uint8_t *)&str[read_len], 1);
read_len++;
if (read_len == cnt - 1|| str[read_len - 1] == '\n') {
stop = true;
break;
}
}
}
MCUBOOT_WATCHDOG_FEED();
esp_rom_delay_us(1000);
} while (!stop);
*newline = (str[read_len - 1] == '\n') ? 1 : 0;
return read_len;
#endif
}
int boot_console_init(void)
{
BOOT_LOG_INF("Initializing serial boot pins");
#ifdef CONFIG_ESP_MCUBOOT_SERIAL_USB_SERIAL_JTAG
usb_serial_jtag_ll_txfifo_flush();
esp_rom_uart_tx_wait_idle(0);
#else
/* Enable GPIO for UART RX */
esp_rom_gpio_pad_select_gpio(SERIAL_BOOT_GPIO_RX);
esp_rom_gpio_connect_in_signal(SERIAL_BOOT_GPIO_RX,
UART_PERIPH_SIGNAL(SERIAL_BOOT_UART_NUM, SOC_UART_RX_PIN_IDX),
0);
gpio_ll_input_enable(&GPIO, SERIAL_BOOT_GPIO_RX);
esp_rom_gpio_pad_pullup_only(SERIAL_BOOT_GPIO_RX);
/* Enable GPIO for UART TX */
esp_rom_gpio_pad_select_gpio(SERIAL_BOOT_GPIO_TX);
esp_rom_gpio_connect_out_signal(SERIAL_BOOT_GPIO_TX,
UART_PERIPH_SIGNAL(SERIAL_BOOT_UART_NUM, SOC_UART_TX_PIN_IDX),
0, 0);
gpio_ll_output_enable(&GPIO, SERIAL_BOOT_GPIO_TX);
uart_ll_set_sclk(serial_boot_uart_dev, UART_SCLK_APB);
uart_ll_set_mode_normal(serial_boot_uart_dev);
uart_ll_set_baudrate(serial_boot_uart_dev, 115200);
uart_ll_set_stop_bits(serial_boot_uart_dev, 1u);
uart_ll_set_parity(serial_boot_uart_dev, UART_PARITY_DISABLE);
uart_ll_set_rx_tout(serial_boot_uart_dev, 16);
uart_ll_set_data_bit_num(serial_boot_uart_dev, UART_DATA_8_BITS);
uart_ll_set_tx_idle_num(serial_boot_uart_dev, 0);
uart_ll_set_hw_flow_ctrl(serial_boot_uart_dev, UART_HW_FLOWCTRL_DISABLE, 100);
periph_ll_enable_clk_clear_rst(PERIPH_UART0_MODULE + SERIAL_BOOT_UART_NUM);
uart_ll_txfifo_rst(serial_boot_uart_dev);
uart_ll_rxfifo_rst(serial_boot_uart_dev);
esp_rom_delay_us(50000);
#endif
return 0;
}
bool boot_serial_detect_pin(void)
{
bool detected = false;
int pin_value = 0;
esp_rom_gpio_pad_select_gpio(SERIAL_BOOT_GPIO_DETECT);
gpio_ll_input_enable(&GPIO, SERIAL_BOOT_GPIO_DETECT);
switch (SERIAL_BOOT_GPIO_INPUT_TYPE) {
// Pull-down
case 0:
gpio_ll_pulldown_en(&GPIO, SERIAL_BOOT_GPIO_DETECT);
break;
// Pull-up
case 1:
gpio_ll_pullup_en(&GPIO, SERIAL_BOOT_GPIO_DETECT);
break;
}
esp_rom_delay_us(50000);
pin_value = gpio_ll_get_level(&GPIO, SERIAL_BOOT_GPIO_DETECT);
detected = (pin_value == SERIAL_BOOT_GPIO_DETECT_VAL);
esp_rom_delay_us(50000);
if (detected) {
if (SERIAL_BOOT_DETECT_DELAY_S > 0) {
/* The delay time is an approximation */
for (int i = 0; i < (SERIAL_BOOT_DETECT_DELAY_S * 100); i++) {
esp_rom_delay_us(10000);
pin_value = gpio_ll_get_level(&GPIO, SERIAL_BOOT_GPIO_DETECT);
detected = (pin_value == SERIAL_BOOT_GPIO_DETECT_VAL);
if (!detected) {
break;
}
}
}
}
return detected;
}

View File

@ -364,6 +364,14 @@ int flash_area_get_sectors(int fa_id, uint32_t *count,
return 0;
}
int flash_area_sector_from_off(uint32_t off, struct flash_sector *sector)
{
sector->fs_off = (off / FLASH_SECTOR_SIZE) * FLASH_SECTOR_SIZE;
sector->fs_size = FLASH_SECTOR_SIZE;
return 0;
}
int flash_area_id_from_multi_image_slot(int image_index, int slot)
{
BOOT_LOG_DBG("%s", __func__);

View File

@ -85,6 +85,19 @@
#if MYNEWT_VAL(BOOTUTIL_BOOTSTRAP)
#define MCUBOOT_BOOTSTRAP 1
#endif
#if MYNEWT_VAL_CHOICE(BOOTUTIL_DOWNGRADE_PREVENTION, version)
#define MCUBOOT_DOWNGRADE_PREVENTION 1
/* MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER is used later as bool value so it is
* always defined, (unlike MCUBOOT_DOWNGRADE_PREVENTION which is only used in
* preprocessor condition and my be not defined) */
#define MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER 0
#elif MYNEWT_VAL_CHOICE(BOOTUTIL_DOWNGRADE_PREVENTION, security_counter)
#define MCUBOOT_DOWNGRADE_PREVENTION 1
#define MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER 1
#endif
#if MYNEWT_VAL(BOOTUTIL_HW_DOWNGRADE_PREVENTION)
#define MCUBOOT_HW_ROLLBACK_PROT 1
#endif
#if MYNEWT_VAL(MCUBOOT_MEASURED_BOOT)
#define MCUBOOT_MEASURED_BOOT 1

View File

@ -76,6 +76,34 @@ syscfg.defs:
BOOTUTIL_MAX_IMG_SECTORS:
description: 'Maximum number of sectors that are swapped.'
value: 128
BOOTUTIL_DOWNGRADE_PREVENTION:
description: >
Select downgrade prevention strategy.
- none downgrades are allowed
- version:
Prevent downgrades by enforcing incrementing version numbers.
When this option is set, any upgrade must have greater major version
or greater minor version with equal major version. This mechanism
only protects against some attacks against version downgrades (for
example, a JTAG could be used to write an older version).
- security_counter:
security counter is used for version eligibility check instead of pure
version. When this option is set, any upgrade must have greater or
equal security counter value.
Because of the acceptance of equal values it allows for software
downgrades to some extent.
choices:
- none
- version
- security_counter
value: none
BOOTUTIL_HW_ROLLBACK_PROT:
description: >
Prevent undesirable/malicious software downgrades. When this option is
set, any upgrade must have greater or equal security counter value.
Because of the acceptance of equal values it allows for software
downgrade to some extent
value: 0
BOOTUTIL_HAVE_LOGGING:
description: 'Enable serial logging'
value: 0

View File

@ -194,10 +194,21 @@ config BOOT_VALIDATE_SLOT0_ONCE
low end devices with as a compromise lowering the security level.
If unsure, leave at the default value.
config BOOT_PREFER_SWAP_MOVE
bool "Prefer the newer swap move algorithm"
default y if SOC_FAMILY_NRF
default n
help
If y, the BOOT_IMAGE_UPGRADE_MODE will default to using
"move" instead of "scratch". This is a separate bool config
option, because Kconfig doesn't allow defaults to be
overridden in choice options. Most devices should be using
swap move.
if !SINGLE_APPLICATION_SLOT
choice BOOT_IMAGE_UPGRADE_MODE
prompt "Image upgrade modes"
default BOOT_SWAP_USING_MOVE if SOC_FAMILY_NRF
default BOOT_SWAP_USING_MOVE if BOOT_PREFER_SWAP_MOVE
default BOOT_SWAP_USING_SCRATCH
config BOOT_SWAP_USING_SCRATCH
@ -537,7 +548,7 @@ choice BOOT_DOWNGRADE_PREVENTION_CHOICE
config MCUBOOT_DOWNGRADE_PREVENTION
bool "SW based downgrade prevention"
depends on BOOT_UPGRADE_ONLY
depends on !BOOT_DIRECT_XIP
help
Prevent downgrades by enforcing incrementing version numbers.
When this option is set, any upgrade must have greater major version
@ -545,6 +556,17 @@ config MCUBOOT_DOWNGRADE_PREVENTION
only protects against some attacks against version downgrades (for
example, a JTAG could be used to write an older version).
config MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER
bool "Use image security counter instead of version number"
depends on MCUBOOT_DOWNGRADE_PREVENTION
depends on (BOOT_SWAP_USING_MOVE || BOOT_SWAP_USING_SCRATCH)
help
Security counter is used for version eligibility check instead of pure
version. When this option is set, any upgrade must have greater or
equal security counter value.
Because of the acceptance of equal values it allows for software
downgrades to some extent.
config MCUBOOT_HW_DOWNGRADE_PREVENTION
bool "HW based downgrade prevention"
help

View File

@ -6,6 +6,3 @@ CONFIG_BOOT_MAX_IMG_SECTORS=256
# MCUboot serial recovery
CONFIG_MCUBOOT_SERIAL=y
CONFIG_BOOT_SERIAL_DETECT_PORT="GPIO_0"
CONFIG_BOOT_SERIAL_DETECT_PIN=5
CONFIG_BOOT_SERIAL_DETECT_PIN_VAL=0

View File

@ -9,9 +9,6 @@ CONFIG_BOOT_MAX_IMG_SECTORS=256
# MCUboot serial recovery
CONFIG_MCUBOOT_SERIAL=y
CONFIG_BOOT_SERIAL_DETECT_PORT="GPIO_0"
CONFIG_BOOT_SERIAL_DETECT_PIN=12
CONFIG_BOOT_SERIAL_DETECT_PIN_VAL=0
CONFIG_BOOT_SERIAL_DETECT_DELAY=450
CONFIG_MCUBOOT_INDICATION_LED=y

View File

@ -17,8 +17,6 @@ CONFIG_UART_LINE_CTRL=y
CONFIG_GPIO=y
CONFIG_MCUBOOT_SERIAL=y
CONFIG_BOOT_SERIAL_CDC_ACM=y
CONFIG_BOOT_SERIAL_DETECT_PORT="GPIO_1"
CONFIG_BOOT_SERIAL_DETECT_PIN=6
# Required by USB
CONFIG_MULTITHREADING=y

View File

@ -9,9 +9,6 @@ CONFIG_BOOT_MAX_IMG_SECTORS=256
# MCUboot serial recovery
CONFIG_MCUBOOT_SERIAL=y
CONFIG_BOOT_SERIAL_DETECT_PORT="GPIO_0"
CONFIG_BOOT_SERIAL_DETECT_PIN=12
CONFIG_BOOT_SERIAL_DETECT_PIN_VAL=0
CONFIG_BOOT_SERIAL_DETECT_DELAY=450
CONFIG_MCUBOOT_INDICATION_LED=y

View File

@ -24,8 +24,6 @@ CONFIG_GPIO=y
CONFIG_MCUBOOT_SERIAL=y
CONFIG_MCUBOOT_SERIAL_DIRECT_IMAGE_UPLOAD=y
CONFIG_BOOT_SERIAL_CDC_ACM=y
CONFIG_BOOT_SERIAL_DETECT_PORT="GPIO_1"
CONFIG_BOOT_SERIAL_DETECT_PIN=13
# Required by QSPI
CONFIG_NORDIC_QSPI_NOR=y

View File

@ -133,6 +133,14 @@
#ifdef CONFIG_MCUBOOT_DOWNGRADE_PREVENTION
#define MCUBOOT_DOWNGRADE_PREVENTION 1
/* MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER is used later as bool value so it is
* always defined, (unlike MCUBOOT_DOWNGRADE_PREVENTION which is only used in
* preprocessor condition and my be not defined) */
# ifdef CONFIG_MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER
# define MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER 1
# else
# define MCUBOOT_DOWNGRADE_PREVENTION_SECURITY_COUNTER 0
# endif
#endif
#ifdef CONFIG_MCUBOOT_HW_DOWNGRADE_PREVENTION

View File

@ -27,6 +27,12 @@
#include <soc.h>
#include <zephyr/linker/linker-defs.h>
#if defined(CONFIG_CPU_AARCH32_CORTEX_A) || defined(CONFIG_CPU_AARCH32_CORTEX_R)
#include <zephyr/arch/arm/aarch32/cortex_a_r/cmsis.h>
#elif defined(CONFIG_CPU_CORTEX_M)
#include <zephyr/arch/arm/aarch32/cortex_m/cmsis.h>
#endif
#include "target.h"
#include "bootutil/bootutil_log.h"
@ -162,20 +168,27 @@ struct arm_vector_table {
static void do_boot(struct boot_rsp *rsp)
{
struct arm_vector_table *vt;
uintptr_t flash_base;
int rc;
/* The beginning of the image is the ARM vector table, containing
* the initial stack pointer address and the reset vector
* consecutively. Manually set the stack pointer and jump into the
* reset vector
*/
#ifdef CONFIG_BOOT_RAM_LOAD
/* Get ram address for image */
vt = (struct arm_vector_table *)(rsp->br_hdr->ih_load_addr + rsp->br_hdr->ih_hdr_size);
#else
uintptr_t flash_base;
int rc;
/* Jump to flash image */
rc = flash_device_base(rsp->br_flash_dev_id, &flash_base);
assert(rc == 0);
vt = (struct arm_vector_table *)(flash_base +
rsp->br_image_off +
rsp->br_hdr->ih_hdr_size);
#endif
sys_clock_disable();

View File

@ -152,8 +152,9 @@ occurs and the information is spread across multiple areas.
or `ed25519`. This will generate a keypair or private key.
To extract the public key in source file form, use
`imgtool getpub -k <input.pem> -l <lang>`, where lang can be one of `c` or
`rust` (defaults to `c`).
`imgtool getpub -k <input.pem> -e <encoding>`, where `encoding` can be one of
`lang-c` or `lang-rust` (defaults to `lang-c`). To extract a public key in PEM
format, use `imgtool getpub -k <input.pem> -e pem`.
If using AES-KW, follow the steps in the next section to generate the
required keys.

View File

@ -552,7 +552,7 @@ Serial recovery mode allows management through MCUMGR (more information and how
---
***Note***
Supported on ESP32.
Supported on ESP32 and ESP32-C3.
---
@ -581,6 +581,28 @@ When enabled, the bootloader checks the if the GPIO `<CONFIG_ESP_SERIAL_BOOT_GPI
Serial mode then uses the UART port configured for communication (`<CONFIG_ESP_SERIAL_BOOT_UART_NUM>`, pins `<CONFIG_ESP_SERIAL_BOOT_GPIO_RX>`, `<CONFIG_ESP_SERIAL_BOOT_GPIO_RX>`).
### [Serial Recovery through USB JTAG Serial port](#serial-recovery-through-usb-jtag-serial-port)
Some chips, like ESP32-C3, have an integrated USB JTAG Serial Controller that implements a serial port (CDC) that can also be used for handling MCUboot Serial Recovery.
More information about the USB pins and hardware configuration on ESP32-C3: https://docs.espressif.com/projects/esp-idf/en/latest/esp32c3/api-guides/usb-serial-jtag-console.html.
Configuration example:
```
# Use Serial through USB JTAG Serial port for Serial Recovery
CONFIG_ESP_MCUBOOT_SERIAL_USB_SERIAL_JTAG=y
# Use sector erasing (recommended) instead of entire image size
# erasing when uploading through Serial Recovery
CONFIG_ESP_MCUBOOT_ERASE_PROGRESSIVELY=y
# GPIO used to boot on Serial Recovery
CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT=5
# GPIO input type (0 for Pull-down, 1 for Pull-up)
CONFIG_ESP_SERIAL_BOOT_GPIO_INPUT_TYPE=0
# GPIO signal value
CONFIG_ESP_SERIAL_BOOT_GPIO_DETECT_VAL=1
# Delay time for identify the GPIO signal
CONFIG_ESP_SERIAL_BOOT_DETECT_DELAY_S=5
```
### [MCUMGR image upload example](#mcumgr-image-upload-example)
After entering the Serial recovery mode on the device, MCUMGR can be used as following:

View File

@ -53,6 +53,10 @@
BOOTLOADER_OVERLAY_CONFIG ?=
BOARD ?= frdm_k64f
SLOT_SIZE ?= 0x60000
BOOT_ADDR ?= 0x0
IMG0_ADDR ?= 0x20000
IMG1_ADDR ?= 0x80000
.PHONY: check boot hello1 clean_boot clean_hello1 \
hello2 clean_hello2 flash_boot flash_hello1 flash_hello2
@ -130,7 +134,7 @@ hello1: check
--header-size $(BOOT_HEADER_LEN) \
--align $(FLASH_ALIGNMENT) \
--version 1.2 \
--slot-size 0x60000 \
--slot-size $(SLOT_SIZE) \
$(BUILD_DIR_HELLO1)/zephyr/zephyr.bin \
signed-hello1.bin
@ -155,7 +159,7 @@ hello2: check
--header-size $(BOOT_HEADER_LEN) \
--align $(FLASH_ALIGNMENT) \
--version 1.2 \
--slot-size 0x60000 \
--slot-size $(SLOT_SIZE) \
--pad \
$(BUILD_DIR_HELLO2)/zephyr/zephyr.bin \
signed-hello2.bin
@ -167,16 +171,16 @@ clean_hello2: check
# are hardcoded at this time.
flash_boot:
$(PYOCD) flash -e chip -a 0 mcuboot.bin
$(PYOCD) flash -e chip -a $(BOOT_ADDR) mcuboot.bin
flash_hello1:
$(PYOCD) flash -a 0x20000 signed-hello1.bin
$(PYOCD) flash -a $(IMG0_ADDR) signed-hello1.bin
flash_hello2:
$(PYOCD) flash -a 0x80000 signed-hello2.bin
$(PYOCD) flash -a $(IMG1_ADDR) signed-hello2.bin
flash_full:
$(PYOCD) flash -e chip -a 0 full.bin
$(PYOCD) flash -e chip -a $(BOOT_ADDR) full.bin
# These test- targets reinvoke make with the configuration set to test
# various configurations. This will generally be followed by using

View File

@ -33,6 +33,11 @@ class ECDSA256P1Public(KeyClass):
encoding=serialization.Encoding.DER,
format=serialization.PublicFormat.SubjectPublicKeyInfo)
def get_public_pem(self):
return self._get_public().public_bytes(
encoding=serialization.Encoding.PEM,
format=serialization.PublicFormat.SubjectPublicKeyInfo)
def get_private_bytes(self, minimal):
self._unsupported('get_private_bytes')

View File

@ -37,6 +37,9 @@ class KeyClass(object):
indent=" ",
file=file)
def emit_public_pem(self, file=sys.stdout):
print(str(self.get_public_pem(), 'utf-8'), file=file, end='')
def emit_private(self, minimal, file=sys.stdout):
self._emit(
header="const unsigned char enc_priv_key[] = {",

View File

@ -44,6 +44,11 @@ class RSAPublic(KeyClass):
encoding=serialization.Encoding.DER,
format=serialization.PublicFormat.PKCS1)
def get_public_pem(self):
return self._get_public().public_bytes(
encoding=serialization.Encoding.PEM,
format=serialization.PublicFormat.SubjectPublicKeyInfo)
def get_private_bytes(self, minimal):
self._unsupported('get_private_bytes')

View File

@ -34,6 +34,11 @@ class X25519Public(KeyClass):
encoding=serialization.Encoding.DER,
format=serialization.PublicFormat.SubjectPublicKeyInfo)
def get_public_pem(self):
return self._get_public().public_bytes(
encoding=serialization.Encoding.PEM,
format=serialization.PublicFormat.SubjectPublicKeyInfo)
def get_private_bytes(self, minimal):
self._unsupported('get_private_bytes')

View File

@ -60,6 +60,7 @@ def gen_x25519(keyfile, passwd):
valid_langs = ['c', 'rust']
valid_encodings = ['lang-c', 'lang-rust', 'pem']
keygens = {
'rsa-2048': gen_rsa2048,
'rsa-3072': gen_rsa3072,
@ -113,20 +114,34 @@ def keygen(type, key, password):
keygens[type](key, password)
@click.option('-l', '--lang', metavar='lang', default=valid_langs[0],
type=click.Choice(valid_langs))
@click.option('-l', '--lang', metavar='lang',
type=click.Choice(valid_langs),
help='This option is deprecated. Please use the '
'`--encoding` option. '
'Valid langs: {}'.format(', '.join(valid_langs)))
@click.option('-e', '--encoding', metavar='encoding',
type=click.Choice(valid_encodings),
help='Valid encodings: {}'.format(', '.join(valid_encodings)))
@click.option('-k', '--key', metavar='filename', required=True)
@click.command(help='Dump public key from keypair')
def getpub(key, lang):
def getpub(key, encoding, lang):
if encoding and lang:
raise click.UsageError('Please use only one of `--encoding/-e` or `--lang/-l`')
elif not encoding and not lang:
# Preserve old behavior defaulting to `c`. If `lang` is removed,
# `default=valid_encodings[0]` should be added to `-e` param.
lang = valid_langs[0]
key = load_key(key)
if key is None:
print("Invalid passphrase")
elif lang == 'c':
elif lang == 'c' or encoding == 'lang-c':
key.emit_c_public()
elif lang == 'rust':
elif lang == 'rust' or encoding == 'lang-rust':
key.emit_rust_public()
elif encoding == 'pem':
key.emit_public_pem()
else:
raise ValueError("BUG: should never get here!")
raise click.UsageError()
@click.option('--minimal', default=False, is_flag=True,

View File

@ -291,6 +291,29 @@ impl ImagesBuilder {
}
}
pub fn make_oversized_secondary_slot_image(self) -> Images {
let mut bad_flash = self.flash;
let ram = self.ram.clone(); // TODO: Avoid this clone.
let images = self.slots.into_iter().enumerate().map(|(image_num, slots)| {
let dep = BoringDep::new(image_num, &NO_DEPS);
let primaries = install_image(&mut bad_flash, &slots[0],
maximal(32784), &ram, &dep, false);
let upgrades = install_image(&mut bad_flash, &slots[1],
ImageSize::Oversized, &ram, &dep, false);
OneImage {
slots,
primaries,
upgrades,
}}).collect();
Images {
flash: bad_flash,
areadesc: self.areadesc,
images,
total_count: None,
ram: self.ram,
}
}
pub fn make_erased_secondary_image(self) -> Images {
let mut flash = self.flash;
let ram = self.ram.clone(); // TODO: Avoid this clone.
@ -335,6 +358,28 @@ impl ImagesBuilder {
}
}
pub fn make_oversized_bootstrap_image(self) -> Images {
let mut flash = self.flash;
let ram = self.ram.clone(); // TODO: Avoid this clone.
let images = self.slots.into_iter().enumerate().map(|(image_num, slots)| {
let dep = BoringDep::new(image_num, &NO_DEPS);
let primaries = install_no_image();
let upgrades = install_image(&mut flash, &slots[1],
ImageSize::Oversized, &ram, &dep, false);
OneImage {
slots,
primaries,
upgrades,
}}).collect();
Images {
flash,
areadesc: self.areadesc,
images,
total_count: None,
ram: self.ram,
}
}
/// Build the Flash and area descriptor for a given device.
pub fn make_device(device: DeviceName, align: usize, erased_val: u8) -> (SimMultiFlash, AreaDesc, &'static [Caps]) {
match device {
@ -512,6 +557,39 @@ impl Images {
fails > 0
}
pub fn run_oversized_bootstrap(&self) -> bool {
let mut flash = self.flash.clone();
let mut fails = 0;
if Caps::Bootstrap.present() {
info!("Try bootstraping image in the primary");
let boot_result = c::boot_go(&mut flash, &self.areadesc, None, None, false).interrupted();
if boot_result {
warn!("Failed first boot");
fails += 1;
}
if self.verify_images(&flash, 0, 1) {
warn!("Image in the first slot was not bootstrapped");
fails += 1;
}
if self.verify_trailers(&flash, 0, BOOT_MAGIC_GOOD,
BOOT_FLAG_SET, BOOT_FLAG_SET) {
warn!("Mismatched trailer for the primary slot");
fails += 1;
}
}
if fails > 0 {
error!("Expected trailer on secondary slot to be erased");
}
fails > 0
}
/// Test a simple upgrade, with dependencies given, and verify that the
/// image does as is described in the test.
@ -724,6 +802,53 @@ impl Images {
fails > 0
}
// Test taht too big upgrade image will be rejected
pub fn run_oversizefail_upgrade(&self) -> bool {
let mut flash = self.flash.clone();
let mut fails = 0;
info!("Try upgrade image with to big size");
// Only perform this test if an upgrade is expected to happen.
if !Caps::modifies_flash() {
info!("Skipping upgrade image with bad signature");
return false;
}
self.mark_upgrades(&mut flash, 0);
self.mark_permanent_upgrades(&mut flash, 0);
self.mark_upgrades(&mut flash, 1);
if !self.verify_trailers(&flash, 0, BOOT_MAGIC_GOOD,
BOOT_FLAG_SET, BOOT_FLAG_UNSET) {
warn!("1. Mismatched trailer for the primary slot");
fails += 1;
}
// Run the bootloader...
if !c::boot_go(&mut flash, &self.areadesc, None, None, false).success() {
warn!("Failed first boot");
fails += 1;
}
// State should not have changed
if !self.verify_images(&flash, 0, 0) {
warn!("Failed image verification");
fails += 1;
}
if !self.verify_trailers(&flash, 0, BOOT_MAGIC_GOOD,
BOOT_FLAG_SET, BOOT_FLAG_UNSET) {
warn!("2. Mismatched trailer for the primary slot");
fails += 1;
}
if fails > 0 {
error!("Expected an upgrade failure when image has to big size");
}
fails > 0
}
// Test that an upgrade is rejected. Assumes that the image was build
// such that the upgrade is instead a downgrade.
pub fn run_nodowngrade(&self) -> bool {
@ -1485,6 +1610,40 @@ enum ImageSize {
Given(usize),
/// Make the image as large as it can be for the partition/device.
Largest,
/// Make the image quite larger than it can be for the partition/device/
Oversized,
}
#[cfg(not(feature = "max-align-32"))]
fn tralier_estimation(dev: &dyn Flash) -> usize {
c::boot_trailer_sz(dev.align() as u32) as usize
}
#[cfg(feature = "max-align-32")]
fn tralier_estimation(dev: &dyn Flash) -> usize {
let sector_size = dev.sector_iter().next().unwrap().size as u32;
align_up(c::boot_trailer_sz(dev.align() as u32), sector_size) as usize
}
fn image_largest_trailer(dev: &dyn Flash) -> usize {
// Using the header size we know, the trailer size, and the slot size, we can compute
// the largest image possible.
let trailer = if Caps::OverwriteUpgrade.present() {
// This computation is incorrect, and we need to figure out the correct size.
// c::boot_status_sz(dev.align() as u32) as usize
16 + 4 * dev.align()
} else if Caps::SwapUsingMove.present() {
let sector_size = dev.sector_iter().next().unwrap().size as u32;
align_up(c::boot_trailer_sz(dev.align() as u32), sector_size) as usize
} else if Caps::SwapUsingScratch.present() {
tralier_estimation(dev)
} else {
panic!("The maximum image size can't be calculated.")
};
trailer
}
/// Install a "program" into the given image. This fakes the image header, or at least all of the
@ -1516,21 +1675,22 @@ fn install_image(flash: &mut SimMultiFlash, slot: &SlotInfo, len: ImageSize,
let len = match len {
ImageSize::Given(size) => size,
ImageSize::Largest => {
// Using the header size we know, the trailer size, and the slot size, we can compute
// the largest image possible.
let trailer = if Caps::OverwriteUpgrade.present() {
// This computation is incorrect, and we need to figure out the correct size.
// c::boot_status_sz(dev.align() as u32) as usize
16 + 4 * dev.align()
} else {
let sector_size = dev.sector_iter().next().unwrap().size as u32;
align_up(c::boot_trailer_sz(dev.align() as u32), sector_size) as usize
};
let trailer = image_largest_trailer(dev);
let tlv_len = tlv.estimate_size();
info!("slot: 0x{:x}, HDR: 0x{:x}, trailer: 0x{:x}",
slot_len, HDR_SIZE, trailer);
slot_len - HDR_SIZE - trailer - tlv_len
},
ImageSize::Oversized => {
let trailer = image_largest_trailer(dev);
let tlv_len = tlv.estimate_size();
info!("slot: 0x{:x}, HDR: 0x{:x}, trailer: 0x{:x}",
slot_len, HDR_SIZE, trailer);
// the overflow size is rougly estimated to work for all
// configurations. It might be precise if tlv_len will be maked precise.
slot_len - HDR_SIZE - trailer - tlv_len + dev.align()*4
}
};
// Generate a boot header. Note that the size doesn't include the header.

View File

@ -49,12 +49,17 @@ macro_rules! sim_test {
sim_test!(bad_secondary_slot, make_bad_secondary_slot_image(), run_signfail_upgrade());
sim_test!(secondary_trailer_leftover, make_erased_secondary_image(), run_secondary_leftover_trailer());
sim_test!(bootstrap, make_bootstrap_image(), run_bootstrap());
sim_test!(oversized_bootstrap, make_oversized_bootstrap_image(), run_oversized_bootstrap());
sim_test!(norevert_newimage, make_no_upgrade_image(&NO_DEPS), run_norevert_newimage());
sim_test!(basic_revert, make_image(&NO_DEPS, true), run_basic_revert());
sim_test!(revert_with_fails, make_image(&NO_DEPS, false), run_revert_with_fails());
sim_test!(perm_with_fails, make_image(&NO_DEPS, true), run_perm_with_fails());
sim_test!(perm_with_random_fails, make_image(&NO_DEPS, true), run_perm_with_random_fails(5));
sim_test!(norevert, make_image(&NO_DEPS, true), run_norevert());
#[cfg(not(feature = "max-align-32"))]
sim_test!(oversized_secondary_slot, make_oversized_secondary_slot_image(), run_oversizefail_upgrade());
sim_test!(status_write_fails_complete, make_image(&NO_DEPS, true), run_with_status_fails_complete());
sim_test!(status_write_fails_with_reset, make_image(&NO_DEPS, true), run_with_status_fails_with_reset());
sim_test!(downgrade_prevention, make_image(&REV_DEPS, true), run_nodowngrade());