canbootloder:Make support for ALT Bootloader an Option

This commit is contained in:
David Sidrane 2021-02-11 06:48:50 -08:00 committed by Daniel Agar
parent 174f2624df
commit 5ea56af5f0
6 changed files with 23 additions and 10 deletions

View File

@ -616,6 +616,7 @@ typedef enum reset_mode_e {
int board_configure_reset(reset_mode_e mode, uint32_t arg);
#endif
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
/****************************************************************************
* Name: board_booted_by_px4
*
@ -631,7 +632,7 @@ int board_configure_reset(reset_mode_e mode, uint32_t arg);
****************************************************************************/
bool board_booted_by_px4(void);
#endif
/************************************************************************************
* Name: board_query_manifest
*

View File

@ -84,8 +84,6 @@
#pragma message "******** DANGER DEBUG_APPLICATION_INPLACE is DEFINED ******"
#endif
extern bootloader_alt_app_shared_t _sapp_bl_shared;
typedef volatile struct bootloader_t {
can_speed_t bus_speed;
volatile uint8_t health;
@ -1104,7 +1102,7 @@ __EXPORT int main(int argc, char *argv[])
bootloader.app_bl_request = (OK == bootloader_app_shared_read(&common, App)) &&
common.bus_speed && common.node_id;
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
/* Was this boot a result of An Alternate Application being told it has a FW update ? */
bootloader_alt_app_shared_t *ps = (bootloader_alt_app_shared_t *) &_sapp_bl_shared;
@ -1117,6 +1115,7 @@ __EXPORT int main(int argc, char *argv[])
ps->signature = 0;
}
#endif
/*
* Mark CRC to say this is not from
* auto baud and Node Allocation

View File

@ -131,6 +131,7 @@ int board_reset(int status)
#endif /* CONFIG_BOARDCTL_RESET */
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
/****************************************************************************
* Name: board_booted_by_px4
*
@ -152,3 +153,4 @@ bool board_booted_by_px4(void)
return (vectors[2] == vectors[3]) && (vectors[4] == vectors[5]);
}
#endif

View File

@ -34,6 +34,7 @@
#include <nuttx/config.h>
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
#include <stdint.h>
#include <string.h>
@ -46,8 +47,6 @@
#include <lib/systemlib/crc.h>
extern void *_sapp_bl_shared;
/****************************************************************************
* Name: bootloader_alt_app_shared_read
*
@ -142,3 +141,4 @@ __EXPORT void bootloader_alt_app_shared_invalidate(void)
bootloader_alt_app_shared->signature = 0;
}
#endif

View File

@ -35,7 +35,7 @@
#pragma once
#include <nuttx/compiler.h>
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
__BEGIN_DECLS
/****************************************************************************
@ -73,6 +73,7 @@ typedef begin_packed_struct struct bootloader_alt_app_shared_t {
} end_packed_struct bootloader_alt_app_shared_t;
#pragma GCC diagnostic pop
extern bootloader_alt_app_shared_t _sapp_bl_shared;
/****************************************************************************
* Name: bootloader_alt_app_shared_read
@ -144,3 +145,4 @@ void bootloader_alt_app_shared_write(bootloader_alt_app_shared_t *alt_shared);
void bootloader_alt_app_shared_invalidate(void);
__END_DECLS
#endif

View File

@ -251,17 +251,19 @@ void UavcanNode::cb_beginfirmware_update(const uavcan::ReceivedDataStructure<Uav
if (!inprogress) {
inprogress = true;
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
if (!board_booted_by_px4()) {
bootloader_alt_app_shared_t shared_alt{0};
shared_alt.fw_server_node_id = req.source_node_id;
shared_alt.node_id = _node.getNodeID().get();
shared_alt.path[0] = '\0';
strncat((char *)shared_alt.path, (const char *)req.image_file_remote_path.path.c_str(), sizeof(shared_alt.path) - 1);
bootloader_alt_app_shared_write(&shared_alt);
board_configure_reset(BOARD_RESET_MODE_CAN_BL, shared_alt.node_id);
}
#endif
bootloader_app_shared_t shared;
shared.bus_speed = active_bitrate;
shared.node_id = _node.getNodeID().get();
@ -527,17 +529,24 @@ extern "C" int uavcannode_start(int argc, char *argv[])
} else {
// Node ID
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
if (!board_booted_by_px4()) {
node_id = 0;
bitrate = 1000000;
} else {
} else
#endif
{
(void)param_get(param_find("CANNODE_NODE_ID"), &node_id);
(void)param_get(param_find("CANNODE_BITRATE"), &bitrate);
}
}
if (board_booted_by_px4() && (node_id < 0 || node_id > uavcan::NodeID::Max || !uavcan::NodeID(node_id).isUnicast())) {
if (
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
board_booted_by_px4() &&
#endif
(node_id < 0 || node_id > uavcan::NodeID::Max || !uavcan::NodeID(node_id).isUnicast())) {
PX4_ERR("Invalid Node ID %i", node_id);
return 1;
}