Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Bootloader/network.cpp
Views: 1798
/*1support for networking enabled bootloader2*/34#include "network.h"56#if AP_BOOTLOADER_NETWORK_ENABLED78#include <AP_Networking/AP_Networking.h>9#include <AP_Networking/AP_Networking_ChibiOS.h>10#include <AP_Networking/AP_Networking_CAN.h>1112#include <lwip/ip_addr.h>13#include <lwip/tcpip.h>14#include <lwip/netifapi.h>15#include <lwip/etharp.h>16#if LWIP_DHCP17#include <lwip/dhcp.h>18#endif19#include <hal.h>20#include "../../modules/ChibiOS/os/various/evtimer.h"21#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>22#include <AP_HAL/utility/Socket.h>23#include <AP_ROMFS/AP_ROMFS.h>24#include "support.h"25#include "bl_protocol.h"26#include <AP_CheckFirmware/AP_CheckFirmware.h>27#include "app_comms.h"28#include "can.h"29#include <stdio.h>30#include <stdarg.h>31#include <AP_HAL_ChibiOS/hwdef/common/flash.h>32#include <AP_HAL_ChibiOS/CANIface.h>3334#ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_MAC_ADDR35#define AP_NETWORKING_BOOTLOADER_DEFAULT_MAC_ADDR "C2:AF:51:03:CF:46"36#endif3738#ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_IP39#define AP_NETWORKING_BOOTLOADER_DEFAULT_IP "192.168.1.100"40#endif4142#ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_GATEWAY43#define AP_NETWORKING_BOOTLOADER_DEFAULT_GATEWAY "192.168.1.1"44#endif4546#ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_NETMASK47#define AP_NETWORKING_BOOTLOADER_DEFAULT_NETMASK "255.255.255.0"48#endif4950#ifndef AP_BOOTLOADER_NETWORK_USE_DHCP51#define AP_BOOTLOADER_NETWORK_USE_DHCP 052#endif5354#define LWIP_SEND_TIMEOUT_MS 5055#define LWIP_NETIF_MTU 150056#define LWIP_LINK_POLL_INTERVAL TIME_S2I(5)5758#define PERIODIC_TIMER_ID 159#define FRAME_RECEIVED_ID 26061#define MIN(a,b) ((a)<(b)?(a):(b))6263static AP_Networking_CAN mcast_server;6465void BL_Network::link_up_cb(void *p)66{67auto *driver = (BL_Network *)p;68#if AP_BOOTLOADER_NETWORK_USE_DHCP69dhcp_start(driver->thisif);70#endif71char ipstr[IP4_STR_LEN];72can_printf("IP %s", SocketAPM::inet_addr_to_str(ntohl(driver->thisif->ip_addr.addr), ipstr, sizeof(ipstr)));7374// start mcast CAN server75mcast_server.start((1U<<HAL_NUM_CAN_IFACES)-1);76}7778void BL_Network::link_down_cb(void *p)79{80#if AP_BOOTLOADER_NETWORK_USE_DHCP81auto *driver = (BL_Network *)p;82dhcp_stop(driver->thisif);83#endif84}8586/*87* This function does the actual transmission of the packet. The packet is88* contained in the pbuf that is passed to the function. This pbuf89* might be chained.90*91* @param netif the lwip network interface structure for this ethernetif92* @param p the MAC packet to send (e.g. IP packet including MAC addresses and type)93* @return ERR_OK if the packet could be sent94* an err_t value if the packet couldn't be sent95*96* @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to97* strange results. You might consider waiting for space in the DMA queue98* to become available since the stack doesn't retry to send a packet99* dropped because of memory failure (except for the TCP timers).100*/101int8_t BL_Network::low_level_output(struct netif *netif, struct pbuf *p)102{103struct pbuf *q;104MACTransmitDescriptor td;105(void)netif;106107if (macWaitTransmitDescriptor(ÐD1, &td, TIME_MS2I(LWIP_SEND_TIMEOUT_MS)) != MSG_OK) {108return ERR_TIMEOUT;109}110111#if ETH_PAD_SIZE112pbuf_header(p, -ETH_PAD_SIZE); /* drop the padding word */113#endif114115/* Iterates through the pbuf chain. */116for(q = p; q != NULL; q = q->next) {117macWriteTransmitDescriptor(&td, (uint8_t *)q->payload, (size_t)q->len);118}119macReleaseTransmitDescriptorX(&td);120121#if ETH_PAD_SIZE122pbuf_header(p, ETH_PAD_SIZE); /* reclaim the padding word */123#endif124125return ERR_OK;126}127128/*129* Receives a frame.130* Allocates a pbuf and transfers the bytes of the incoming131* packet from the interface into the pbuf.132*133* @param netif the lwip network interface structure for this ethernetif134* @return a pbuf filled with the received packet (including MAC header)135* NULL on memory error136*/137bool BL_Network::low_level_input(struct netif *netif, struct pbuf **pbuf)138{139MACReceiveDescriptor rd;140struct pbuf *q;141u16_t len;142143(void)netif;144145if (macWaitReceiveDescriptor(ÐD1, &rd, TIME_IMMEDIATE) != MSG_OK) {146return false;147}148149len = (u16_t)rd.size;150151#if ETH_PAD_SIZE152len += ETH_PAD_SIZE; /* allow room for Ethernet padding */153#endif154155/* We allocate a pbuf chain of pbufs from the pool. */156*pbuf = pbuf_alloc(PBUF_RAW, len, PBUF_POOL);157158if (*pbuf != nullptr) {159#if ETH_PAD_SIZE160pbuf_header(*pbuf, -ETH_PAD_SIZE); /* drop the padding word */161#endif162163/* Iterates through the pbuf chain. */164for(q = *pbuf; q != NULL; q = q->next) {165macReadReceiveDescriptor(&rd, (uint8_t *)q->payload, (size_t)q->len);166}167macReleaseReceiveDescriptorX(&rd);168169#if ETH_PAD_SIZE170pbuf_header(*pbuf, ETH_PAD_SIZE); /* reclaim the padding word */171#endif172} else {173macReleaseReceiveDescriptorX(&rd); // Drop packet174}175176return true;177}178179int8_t BL_Network::ethernetif_init(struct netif *netif)180{181netif->state = NULL;182netif->name[0] = 'm';183netif->name[1] = 's';184netif->output = etharp_output;185netif->linkoutput = low_level_output;186187/* set MAC hardware address length */188netif->hwaddr_len = ETHARP_HWADDR_LEN;189190/* maximum transfer unit */191netif->mtu = LWIP_NETIF_MTU;192193/* device capabilities */194netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP;195196#if LWIP_IGMP197// also enable multicast198netif->flags |= NETIF_FLAG_IGMP;199#endif200201return ERR_OK;202}203204/*205networking thread206*/207void BL_Network::net_thread()208{209/* start tcpip thread */210tcpip_init(NULL, NULL);211212thread_sleep_ms(100);213214AP_Networking::convert_str_to_macaddr(AP_NETWORKING_BOOTLOADER_DEFAULT_MAC_ADDR, thisif->hwaddr);215216ip4_addr_t ip, gateway, netmask;217if (addr.ip == 0) {218// no IP from AP_Periph, use defaults219ip.addr = htonl(SocketAPM::inet_str_to_addr(AP_NETWORKING_BOOTLOADER_DEFAULT_IP));220gateway.addr = htonl(SocketAPM::inet_str_to_addr(AP_NETWORKING_BOOTLOADER_DEFAULT_GATEWAY));221netmask.addr = htonl(SocketAPM::inet_str_to_addr(AP_NETWORKING_BOOTLOADER_DEFAULT_NETMASK));222} else {223// use addresses from AP_Periph224ip.addr = htonl(addr.ip);225netmask.addr = htonl(addr.netmask);226gateway.addr = htonl(addr.gateway);227}228229const MACConfig mac_config = {thisif->hwaddr};230macStart(ÐD1, &mac_config);231232/* Add interface. */233234auto result = netifapi_netif_add(thisif, &ip, &netmask, &gateway, NULL, ethernetif_init, tcpip_input);235if (result != ERR_OK) {236AP_HAL::panic("Failed to initialise netif");237}238239netifapi_netif_set_default(thisif);240netifapi_netif_set_up(thisif);241242/* Setup event sources.*/243event_timer_t evt;244event_listener_t el0, el1;245246evtObjectInit(&evt, LWIP_LINK_POLL_INTERVAL);247evtStart(&evt);248chEvtRegisterMask(&evt.et_es, &el0, PERIODIC_TIMER_ID);249chEvtRegisterMaskWithFlags(macGetEventSource(ÐD1), &el1,250FRAME_RECEIVED_ID, MAC_FLAGS_RX);251chEvtAddEvents(PERIODIC_TIMER_ID | FRAME_RECEIVED_ID);252253while (true) {254eventmask_t mask = chEvtWaitAny(ALL_EVENTS);255if (mask & PERIODIC_TIMER_ID) {256bool current_link_status = macPollLinkStatus(ÐD1);257if (current_link_status != netif_is_link_up(thisif)) {258if (current_link_status) {259tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_up, thisif, 0);260tcpip_callback_with_block(link_up_cb, this, 0);261}262else {263tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_down, thisif, 0);264tcpip_callback_with_block(link_down_cb, this, 0);265}266}267}268269if (mask & FRAME_RECEIVED_ID) {270struct pbuf *p;271while (low_level_input(thisif, &p)) {272if (p != NULL) {273struct eth_hdr *ethhdr = (struct eth_hdr *)p->payload;274switch (htons(ethhdr->type)) {275/* IP or ARP packet? */276case ETHTYPE_IP:277case ETHTYPE_ARP:278/* full packet send to tcpip_thread to process */279if (thisif->input(p, thisif) == ERR_OK) {280break;281}282/* Falls through */283default:284pbuf_free(p);285}286}287}288}289}290}291292void BL_Network::net_thread_trampoline(void *ctx)293{294auto *net = (BL_Network *)ctx;295net->net_thread();296}297298void BL_Network::web_server_trampoline(void *ctx)299{300auto *net = (BL_Network *)ctx;301net->web_server();302}303304#define STR_HELPER(x) #x305#define STR(x) STR_HELPER(x)306307BL_Network::web_var BL_Network::variables[] = {308{ "BOARD_NAME", CHIBIOS_BOARD_NAME },309{ "BOARD_ID", STR(APJ_BOARD_ID) },310{ "FLASH_SIZE", STR(BOARD_FLASH_SIZE) },311};312313/*314substitute variables of the form {VARNAME}315*/316char *BL_Network::substitute_vars(const char *str, uint32_t size)317{318// assume 1024 is enough room for new variables319char *result = (char *)malloc(strlen(str) + 1024);320if (result == nullptr) {321return nullptr;322}323char *p = result;324const char *str0 = str;325while (*str && str-str0<size) {326if (*str != '{') {327*p++ = *str++;328continue;329}330char *q = strchr(str+1, '}');331if (q == nullptr) {332*p++ = *str++;333continue;334}335const uint32_t len = (q - str)-1;336bool found = false;337for (auto &v : variables) {338if (strlen(v.name) == len && strncmp(v.name, str+1, len) == 0) {339found = true;340strcpy(p, v.value);341p += strlen(v.value);342str = q+1;343break;344}345}346if (found) {347continue;348}349*p++ = *str++;350}351*p = '\0';352return result;353}354355/*356read HTTP headers, returing as a single string357*/358char *BL_Network::read_headers(SocketAPM *sock)359{360char *ret = (char *)malloc(1024);361char *p = ret;362while (true) {363char c;364auto n = sock->recv(&c, 1, 100);365if (n != 1) {366break;367}368*p++ = c;369if (p-ret >= 4 && strcmp(p-4, "\r\n\r\n") == 0) {370break;371}372}373return ret;374}375376/*377handle an incoming HTTP POST request378*/379void BL_Network::handle_post(SocketAPM *sock, uint32_t content_length)380{381/*382skip over form boundary. We don't care about the filename as we383only support one file384*/385uint8_t state = 0;386while (true) {387char c;388if (sock->recv(&c, 1, 100) != 1) {389return;390}391content_length--;392// absorb up to \r\n\r\n393if (c == '\r') {394if (state == 2) {395state = 3;396} else {397state = 1;398}399} else if (c == '\n') {400if (state == 1 || state == 3) {401state++;402} else {403state = 0;404}405if (state == 4) {406break;407}408} else {409state = 0;410}411}412/*413erase all of flash414*/415status_printf("Erasing ...");416flash_set_keep_unlocked(true);417uint32_t sec=0;418while (flash_func_sector_size(sec) != 0 &&419flash_func_erase_sector(sec)) {420thread_sleep_ms(10);421sec++;422if (stm32_flash_getpageaddr(sec) - stm32_flash_getpageaddr(0) >= content_length) {423break;424}425}426/*427receive file and write to flash428*/429uint32_t buf[128];430uint32_t ofs = 0;431432// must be multiple of 4433content_length &= ~3;434435const uint32_t max_ofs = MIN(BOARD_FLASH_SIZE*1024, content_length);436uint8_t last_pct = 0;437while (ofs < max_ofs) {438const uint32_t needed = MIN(sizeof(buf), max_ofs-ofs);439auto n = sock->recv((void*)buf, needed, 10000);440if (n <= 0) {441break;442}443// we need a whole number of words444if (n % 4 != 0 && n < needed) {445auto n2 = sock->recv(((uint8_t*)buf)+n, 4 - n%4, 10000);446if (n2 > 0) {447n += n2;448}449}450flash_write_buffer(ofs, buf, n/4);451ofs += n;452uint8_t pct = ofs*100/max_ofs;453if (pct % 10 == 0 && last_pct != pct) {454last_pct = pct;455status_printf("Flashing %u%%", unsigned(pct));456}457}458if (ofs % 32 != 0) {459// pad to 32 bytes460memset(buf, 0xff, sizeof(buf));461flash_write_buffer(ofs, buf, (32 - ofs%32)/4);462}463flash_write_flush();464flash_set_keep_unlocked(false);465const auto ok = check_good_firmware();466if (ok == check_fw_result_t::CHECK_FW_OK) {467need_launch = true;468status_printf("Flash done: OK");469const char *str = "<html><head><meta http-equiv=\"refresh\" content=\"4; url=/\"></head><body>Flash OK, booting</body></html>";470sock->send(str, strlen(str));471} else {472status_printf("Flash done: ERR:%u", unsigned(ok));473}474}475476/*477handle an incoming HTTP request478*/479void BL_Network::handle_request(SocketAPM *sock)480{481/*482read HTTP headers483*/484char *headers = read_headers(sock);485486const char *header = "HTTP/1.1 200 OK\r\n"487"Content-Type: text/html\r\n"488"Connection: close\r\n"489"\r\n";490sock->send(header, strlen(header));491492if (strncmp(headers, "POST / ", 7) == 0) {493const char *clen1 = "\r\nContent-Length:";494const char *clen2 = "\r\ncontent-length:";495const char *p = strstr(headers, clen1);496if (p == nullptr) {497p = strstr(headers, clen2);498}499if (p != nullptr) {500p += strlen(clen1);501const uint32_t content_length = atoi(p);502handle_post(sock, content_length);503delete headers;504delete sock;505return;506}507}508509/*510check for async status511*/512const char *get_status = "GET /bootloader_status.html";513if (strncmp(headers, get_status, strlen(get_status)) == 0) {514{515WITH_SEMAPHORE(status_mtx);516sock->send(bl_status, strlen(bl_status));517}518delete headers;519delete sock;520return;521}522523const char *get_reboot = "GET /REBOOT";524if (strncmp(headers, get_reboot, strlen(get_reboot)) == 0) {525need_reboot = true;526}527528uint32_t size = 0;529const auto *msg = AP_ROMFS::find_decompress("index.html", size);530if (need_reboot) {531const char *str = "<html><head><meta http-equiv=\"refresh\" content=\"2; url=/\"></head></html>";532sock->send(str, strlen(str));533} else {534char *msg2 = substitute_vars((const char *)msg, size);535sock->send(msg2, strlen(msg2));536delete msg2;537}538delete headers;539delete sock;540AP_ROMFS::free(msg);541}542543struct req_context {544BL_Network *driver;545SocketAPM *sock;546};547548void BL_Network::net_request_trampoline(void *ctx)549{550auto *req = (req_context *)ctx;551req->driver->handle_request(req->sock);552553auto *driver = req->driver;554auto *thd = chThdGetSelfX();555delete req;556557WITH_SEMAPHORE(driver->web_delete_mtx);558thd->delete_next = driver->web_delete_list;559driver->web_delete_list = thd;560}561562/*563web server thread564*/565void BL_Network::web_server(void)566{567auto *listen_socket = NEW_NOTHROW SocketAPM(0);568listen_socket->bind("0.0.0.0", 80);569listen_socket->listen(20);570571while (true) {572auto *sock = listen_socket->accept(20);573if (need_reboot) {574need_reboot = false;575NVIC_SystemReset();576}577if (need_launch) {578need_launch = false;579thread_sleep_ms(1000);580jump_to_app();581}582if (sock == nullptr) {583continue;584}585// a new thread for each connection to allow for AJAX586auto *req = NEW_NOTHROW req_context;587req->driver = this;588req->sock = sock;589thread_create_alloc(THD_WORKING_AREA_SIZE(2048),590"web_request",59160,592net_request_trampoline,593req);594595// cleanup any finished threads596WITH_SEMAPHORE(web_delete_mtx);597while (web_delete_list != nullptr) {598auto *thd = web_delete_list;599web_delete_list = thd->delete_next;600chThdRelease(thd);601}602}603}604605/*606initialise bootloader networking607*/608void BL_Network::init()609{610AP_Networking_ChibiOS::allocate_buffers();611612macInit();613614thisif = NEW_NOTHROW netif;615616net_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(2048),617"network",61860,619net_thread_trampoline,620this);621622thread_create_alloc(THD_WORKING_AREA_SIZE(2048),623"web_server",62460,625web_server_trampoline,626this);627}628629/*630save IP address from AP_Periph631*/632void BL_Network::save_comms_ip(void)633{634struct app_bootloader_comms *comms = (struct app_bootloader_comms *)HAL_RAM0_START;635if (comms->magic == APP_BOOTLOADER_COMMS_MAGIC && comms->ip != 0) {636addr.ip = comms->ip;637addr.netmask = comms->netmask;638addr.gateway = comms->gateway;639}640}641642/*643update status message644*/645void BL_Network::status_printf(const char *fmt, ...)646{647WITH_SEMAPHORE(status_mtx);648va_list ap;649va_start(ap, fmt);650vsnprintf(bl_status, sizeof(bl_status), fmt, ap);651va_end(ap);652can_printf("%s", bl_status);653}654655#endif // AP_BOOTLOADER_NETWORK_ENABLED656657658659