From 7a6ed0281b83aa768bb67b72dd1190412a296da8 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 10 Feb 2021 07:21:11 -0800 Subject: [PATCH] uavcan bootloader:Add support alt boot_alt_app_shared --- src/drivers/bootloaders/CMakeLists.txt | 5 +- src/drivers/bootloaders/boot_alt_app_shared.c | 144 +++++++++++++++++ src/drivers/bootloaders/boot_alt_app_shared.h | 146 ++++++++++++++++++ src/drivers/bootloaders/boot_app_shared.h | 10 -- 4 files changed, 294 insertions(+), 11 deletions(-) create mode 100644 src/drivers/bootloaders/boot_alt_app_shared.c create mode 100644 src/drivers/bootloaders/boot_alt_app_shared.h diff --git a/src/drivers/bootloaders/CMakeLists.txt b/src/drivers/bootloaders/CMakeLists.txt index 3fca22697d..f5bc89a5d9 100644 --- a/src/drivers/bootloaders/CMakeLists.txt +++ b/src/drivers/bootloaders/CMakeLists.txt @@ -31,7 +31,10 @@ # ############################################################################ -add_library(drivers_bootloaders boot_app_shared.c) +add_library(drivers_bootloaders + boot_app_shared.c + boot_alt_app_shared.c + ) add_dependencies(drivers_bootloaders prebuild_targets) include_directories(include) diff --git a/src/drivers/bootloaders/boot_alt_app_shared.c b/src/drivers/bootloaders/boot_alt_app_shared.c new file mode 100644 index 0000000000..ecab7df9bb --- /dev/null +++ b/src/drivers/bootloaders/boot_alt_app_shared.c @@ -0,0 +1,144 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * Author: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +#include +#include + +#include "chip.h" +#include "stm32.h" + +#include + +#include "boot_alt_app_shared.h" + +#include + +extern void *_sapp_bl_shared; + +/**************************************************************************** + * Name: bootloader_alt_app_shared_read + * + * Description: + * Based on the role requested, this function will conditionally populate + * a bootloader_alt_app_shared_t structure from the physical locations used + * to transfer the shared data to/from an application (internal data) . + * + * The functions will only populate the structure and return a status + * indicating success, if the internal data has the correct signature as + * requested by the Role AND has a valid crc. + * + * Input Parameters: + * shared - A pointer to a bootloader_alt_app_shared_t return the data in if + * the internal data is valid for the requested Role + * role - An eRole_t of App or BootLoader to validate the internal data + * against. For a Bootloader this would be the value of App to + * read the application passed data. + * + * Returned value: + * OK - Indicates that the internal data has been copied to callers + * bootloader_alt_app_shared_t structure. + * + * -EBADR - internal data was not valid. The copy did not occur. + * + ****************************************************************************/ +__EXPORT int bootloader_alt_app_shared_read(bootloader_alt_app_shared_t *alt_shared) +{ + int rv = EBADR; + bootloader_alt_app_shared_t *bootloader_alt_app_shared = (bootloader_alt_app_shared_t *)&_sapp_bl_shared; + + if (bootloader_alt_app_shared->signature == BL_ALT_APP_SHARED_SIGNATURE) { + *alt_shared = *bootloader_alt_app_shared; + rv = 0; + } + + return rv; +} + +/**************************************************************************** + * Name: bootloader_alt_app_shared_write + * + * Description: + * Based on the role, this function will commit the data passed + * into the physical locations used to transfer the shared data to/from + * an application (internal data) . + * + * The functions will populate the signature and crc the data + * based on the provided Role. + * + * Input Parameters: + * shared - A pointer to a bootloader_alt_app_shared_t data to commit to + * the internal data for passing to/from an application. + * role - An eRole_t of App or BootLoader to use in the internal data + * to be passed to/from an application. For a Bootloader this + * would be the value of Bootloader to write to the passed data. + * to the application via the internal data. + * + * Returned value: + * None. + * + ****************************************************************************/ +__EXPORT void bootloader_alt_app_shared_write(bootloader_alt_app_shared_t *alt_shared) +{ + + bootloader_alt_app_shared_t *bootloader_alt_app_shared = (bootloader_alt_app_shared_t *)&_sapp_bl_shared; + *bootloader_alt_app_shared = *alt_shared; + bootloader_alt_app_shared->signature = BL_ALT_APP_SHARED_SIGNATURE; + +} + +/**************************************************************************** + * Name: bootloader_app_shared_invalidate + * + * Description: + * Invalidates the data passed the physical locations used to transfer + * the shared data to/from an application (internal data) . + * + * The functions will invalidate the signature and crc and shoulf be used + * to prevent deja vu. + * + * Input Parameters: + * None. + * + * Returned value: + * None. + * + ****************************************************************************/ +__EXPORT void bootloader_alt_app_shared_invalidate(void) +{ + bootloader_alt_app_shared_t *bootloader_alt_app_shared = (bootloader_alt_app_shared_t *)&_sapp_bl_shared; + bootloader_alt_app_shared->signature = 0; + +} diff --git a/src/drivers/bootloaders/boot_alt_app_shared.h b/src/drivers/bootloaders/boot_alt_app_shared.h new file mode 100644 index 0000000000..40e7d7f9e8 --- /dev/null +++ b/src/drivers/bootloaders/boot_alt_app_shared.h @@ -0,0 +1,146 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * Author: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include + +__BEGIN_DECLS + +/**************************************************************************** + * + * Bootloader and Application shared structure. + * + * The data in this structure is passed in SRAM or the the CAN filter + * registers from bootloader to application and application to bootloader. + * + * Do not assume any mapping or location for the passing of this data + * that is done in the read and write routines and is abstracted by design. + * + * For reference, the following is performed based on eRole in API calls + * defined below: + * + * The application must write BOOTLOADER_COMMON_APP_SIGNATURE to the + * signature field when passing data to the bootloader; when the + * bootloader passes data to the application, it must write + * BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE to the signature field. + * + * The CRC is calculated over the structure from signature to the + * last byte. The resulting values are then copied to the CAN filter + * registers by bootloader_app_shared_read and + * bootloader_app_shared_write. + * +****************************************************************************/ + +#define BL_ALT_APP_SHARED_SIGNATURE 0xc544ad9a +typedef begin_packed_struct struct bootloader_alt_app_shared_t { + uint32_t signature; + uint32_t reserved[4]; + uint8_t fw_server_node_id; + uint8_t node_id; + uint8_t path[201]; +} end_packed_struct bootloader_alt_app_shared_t; +#pragma GCC diagnostic pop + + +/**************************************************************************** + * Name: bootloader_alt_app_shared_read + * + * Description: + * Based on the role requested, this function will conditionally populate + * a bootloader_alt_app_shared_t structure from the physical locations used + * to transfer the shared data to/from an application (internal data) . + * + * The functions will only populate the structure and return a status + * indicating success, if the internal data has the correct signature as + * requested by the Role AND has a valid crc. + * + * Input Parameters: + * shared - A pointer to a bootloader_alt_app_shared_t return the data in if + * the internal data is valid for the requested Role + * + * Returned value: + * OK - Indicates that the internal data has been copied to callers + * bootloader_alt_app_shared_t structure. + * + * -EBADR - The Role or crc of the internal data was not valid. The copy + * did not occur. + * + ****************************************************************************/ + +int bootloader_alt_app_shared_read(bootloader_alt_app_shared_t *alt_shared); + +/**************************************************************************** + * Name: bootloader_alt_app_shared_write + * + * Description: + * Based on the role, this function will commit the data passed + * into the physical locations used to transfer the shared data to/from + * an application (internal data) . + * + * The functions will populate the signature and crc the data + * based on the provided Role. + * + * Input Parameters: + * shared - A pointer to a bootloader_alt_app_shared_t data to commit to + * the internal data for passing to/from an application. + * + * Returned value: + * None. + * + ****************************************************************************/ + +void bootloader_alt_app_shared_write(bootloader_alt_app_shared_t *alt_shared); + +/**************************************************************************** + * Name: bootloader_alt_app_shared_invalidate + * + * Description: + * Invalidates the data passed the physical locations used to transfer + * the shared data to/from an application (internal data) . + * + * The functions will invalidate the signature and crc and should be used + * to prevent deja vu. + * + * Input Parameters: + * None. + * + * Returned value: + * None. + * + ****************************************************************************/ + +void bootloader_alt_app_shared_invalidate(void); + +__END_DECLS diff --git a/src/drivers/bootloaders/boot_app_shared.h b/src/drivers/bootloaders/boot_app_shared.h index ace1db5007..ed36d53769 100644 --- a/src/drivers/bootloaders/boot_app_shared.h +++ b/src/drivers/bootloaders/boot_app_shared.h @@ -95,16 +95,6 @@ typedef begin_packed_struct struct bootloader_app_shared_t { uint32_t node_id; } end_packed_struct bootloader_app_shared_t; -#define BL_ALT_APP_SHARED_SIGNATURE 0xc544ad9a -typedef begin_packed_struct struct bootloader_alt_app_shared_t { - uint32_t signature; - uint32_t reserved[4]; - uint8_t fw_server_node_id; - uint8_t node_id; - uint8_t path[201]; -} end_packed_struct bootloader_alt_app_shared_t; -#pragma GCC diagnostic pop - /**************************************************************************** * * Application firmware descriptor.