AP_Periph: added reboot link to web UI

This commit is contained in:
Andrew Tridgell 2024-01-15 13:09:34 +11:00
parent 7c711d7525
commit 9904dca558
4 changed files with 51 additions and 2 deletions

View File

@ -198,6 +198,7 @@ local DYNAMIC_PAGES = {
<div id="main">
<ul>
<li><a href="mnt/">Filesystem Access</a></li>
<li><a href="?FWUPDATE">Reboot for Firmware Update</a></li>
</ul>
</div>
<h2>Controller Status</h2>
@ -219,6 +220,15 @@ local DYNAMIC_PAGES = {
]]
}
reboot_counter = 0
local ACTION_PAGES = {
["/?FWUPDATE"] = function()
periph:can_printf("Rebooting for firmware update")
reboot_counter = 50
end
}
--[[
builtin javascript library functions
--]]
@ -835,6 +845,21 @@ local function Client(_sock, _idx)
end
end
if ACTION_PAGES[path] ~= nil then
DEBUG(string.format("Running ACTION %s", path))
local fn = ACTION_PAGES[path]
self.send_header(200, "OK", {["Content-Type"]=CONTENT_TEXT_HTML})
self.sendstring([[
<html>
<head>
<meta http-equiv="refresh" content="2; url=/">
</head>
</html>
]])
fn()
return
end
if DYNAMIC_PAGES[path] ~= nil then
self.file_download(path)
return
@ -956,6 +981,13 @@ end
local function update()
check_new_clients()
check_clients()
if reboot_counter then
reboot_counter = reboot_counter - 1
if reboot_counter == 0 then
periph:can_printf("Rebooting")
periph:reboot(true)
end
end
return update,5
end

View File

@ -368,8 +368,10 @@ void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance,
{
#if HAL_RAM_RESERVE_START >= 256
// setup information on firmware request at start of ram
struct app_bootloader_comms *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
memset(comms, 0, sizeof(struct app_bootloader_comms));
auto *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
if (comms->magic != APP_BOOTLOADER_COMMS_MAGIC) {
memset(comms, 0, sizeof(*comms));
}
comms->magic = APP_BOOTLOADER_COMMS_MAGIC;
uavcan_protocol_file_BeginFirmwareUpdateRequest req;

View File

@ -181,6 +181,20 @@ void Networking_Periph::update(void)
p.update();
}
#endif
#if HAL_RAM_RESERVE_START >= 256
if (!got_addresses && networking_lib.get_ip_active() != 0) {
got_addresses = true;
auto *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
if (comms->magic != APP_BOOTLOADER_COMMS_MAGIC) {
memset(comms, 0, sizeof(*comms));
}
comms->magic = APP_BOOTLOADER_COMMS_MAGIC;
comms->ip = networking_lib.get_ip_active();
comms->netmask = networking_lib.get_netmask_active();
comms->gateway = networking_lib.get_gateway_active();
}
#endif // HAL_RAM_RESERVE_START
}
#endif // HAL_PERIPH_ENABLE_NETWORKING

View File

@ -62,6 +62,7 @@ private:
#endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU
AP_Networking networking_lib;
bool got_addresses;
#if AP_NETWORKING_BACKEND_PPP
AP_Int8 ppp_port;