CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Bootloader/network.cpp
Views: 1798
1
/*
2
support for networking enabled bootloader
3
*/
4
5
#include "network.h"
6
7
#if AP_BOOTLOADER_NETWORK_ENABLED
8
9
#include <AP_Networking/AP_Networking.h>
10
#include <AP_Networking/AP_Networking_ChibiOS.h>
11
#include <AP_Networking/AP_Networking_CAN.h>
12
13
#include <lwip/ip_addr.h>
14
#include <lwip/tcpip.h>
15
#include <lwip/netifapi.h>
16
#include <lwip/etharp.h>
17
#if LWIP_DHCP
18
#include <lwip/dhcp.h>
19
#endif
20
#include <hal.h>
21
#include "../../modules/ChibiOS/os/various/evtimer.h"
22
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
23
#include <AP_HAL/utility/Socket.h>
24
#include <AP_ROMFS/AP_ROMFS.h>
25
#include "support.h"
26
#include "bl_protocol.h"
27
#include <AP_CheckFirmware/AP_CheckFirmware.h>
28
#include "app_comms.h"
29
#include "can.h"
30
#include <stdio.h>
31
#include <stdarg.h>
32
#include <AP_HAL_ChibiOS/hwdef/common/flash.h>
33
#include <AP_HAL_ChibiOS/CANIface.h>
34
35
#ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_MAC_ADDR
36
#define AP_NETWORKING_BOOTLOADER_DEFAULT_MAC_ADDR "C2:AF:51:03:CF:46"
37
#endif
38
39
#ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_IP
40
#define AP_NETWORKING_BOOTLOADER_DEFAULT_IP "192.168.1.100"
41
#endif
42
43
#ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_GATEWAY
44
#define AP_NETWORKING_BOOTLOADER_DEFAULT_GATEWAY "192.168.1.1"
45
#endif
46
47
#ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_NETMASK
48
#define AP_NETWORKING_BOOTLOADER_DEFAULT_NETMASK "255.255.255.0"
49
#endif
50
51
#ifndef AP_BOOTLOADER_NETWORK_USE_DHCP
52
#define AP_BOOTLOADER_NETWORK_USE_DHCP 0
53
#endif
54
55
#define LWIP_SEND_TIMEOUT_MS 50
56
#define LWIP_NETIF_MTU 1500
57
#define LWIP_LINK_POLL_INTERVAL TIME_S2I(5)
58
59
#define PERIODIC_TIMER_ID 1
60
#define FRAME_RECEIVED_ID 2
61
62
#define MIN(a,b) ((a)<(b)?(a):(b))
63
64
static AP_Networking_CAN mcast_server;
65
66
void BL_Network::link_up_cb(void *p)
67
{
68
auto *driver = (BL_Network *)p;
69
#if AP_BOOTLOADER_NETWORK_USE_DHCP
70
dhcp_start(driver->thisif);
71
#endif
72
char ipstr[IP4_STR_LEN];
73
can_printf("IP %s", SocketAPM::inet_addr_to_str(ntohl(driver->thisif->ip_addr.addr), ipstr, sizeof(ipstr)));
74
75
// start mcast CAN server
76
mcast_server.start((1U<<HAL_NUM_CAN_IFACES)-1);
77
}
78
79
void BL_Network::link_down_cb(void *p)
80
{
81
#if AP_BOOTLOADER_NETWORK_USE_DHCP
82
auto *driver = (BL_Network *)p;
83
dhcp_stop(driver->thisif);
84
#endif
85
}
86
87
/*
88
* This function does the actual transmission of the packet. The packet is
89
* contained in the pbuf that is passed to the function. This pbuf
90
* might be chained.
91
*
92
* @param netif the lwip network interface structure for this ethernetif
93
* @param p the MAC packet to send (e.g. IP packet including MAC addresses and type)
94
* @return ERR_OK if the packet could be sent
95
* an err_t value if the packet couldn't be sent
96
*
97
* @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to
98
* strange results. You might consider waiting for space in the DMA queue
99
* to become available since the stack doesn't retry to send a packet
100
* dropped because of memory failure (except for the TCP timers).
101
*/
102
int8_t BL_Network::low_level_output(struct netif *netif, struct pbuf *p)
103
{
104
struct pbuf *q;
105
MACTransmitDescriptor td;
106
(void)netif;
107
108
if (macWaitTransmitDescriptor(&ETHD1, &td, TIME_MS2I(LWIP_SEND_TIMEOUT_MS)) != MSG_OK) {
109
return ERR_TIMEOUT;
110
}
111
112
#if ETH_PAD_SIZE
113
pbuf_header(p, -ETH_PAD_SIZE); /* drop the padding word */
114
#endif
115
116
/* Iterates through the pbuf chain. */
117
for(q = p; q != NULL; q = q->next) {
118
macWriteTransmitDescriptor(&td, (uint8_t *)q->payload, (size_t)q->len);
119
}
120
macReleaseTransmitDescriptorX(&td);
121
122
#if ETH_PAD_SIZE
123
pbuf_header(p, ETH_PAD_SIZE); /* reclaim the padding word */
124
#endif
125
126
return ERR_OK;
127
}
128
129
/*
130
* Receives a frame.
131
* Allocates a pbuf and transfers the bytes of the incoming
132
* packet from the interface into the pbuf.
133
*
134
* @param netif the lwip network interface structure for this ethernetif
135
* @return a pbuf filled with the received packet (including MAC header)
136
* NULL on memory error
137
*/
138
bool BL_Network::low_level_input(struct netif *netif, struct pbuf **pbuf)
139
{
140
MACReceiveDescriptor rd;
141
struct pbuf *q;
142
u16_t len;
143
144
(void)netif;
145
146
if (macWaitReceiveDescriptor(&ETHD1, &rd, TIME_IMMEDIATE) != MSG_OK) {
147
return false;
148
}
149
150
len = (u16_t)rd.size;
151
152
#if ETH_PAD_SIZE
153
len += ETH_PAD_SIZE; /* allow room for Ethernet padding */
154
#endif
155
156
/* We allocate a pbuf chain of pbufs from the pool. */
157
*pbuf = pbuf_alloc(PBUF_RAW, len, PBUF_POOL);
158
159
if (*pbuf != nullptr) {
160
#if ETH_PAD_SIZE
161
pbuf_header(*pbuf, -ETH_PAD_SIZE); /* drop the padding word */
162
#endif
163
164
/* Iterates through the pbuf chain. */
165
for(q = *pbuf; q != NULL; q = q->next) {
166
macReadReceiveDescriptor(&rd, (uint8_t *)q->payload, (size_t)q->len);
167
}
168
macReleaseReceiveDescriptorX(&rd);
169
170
#if ETH_PAD_SIZE
171
pbuf_header(*pbuf, ETH_PAD_SIZE); /* reclaim the padding word */
172
#endif
173
} else {
174
macReleaseReceiveDescriptorX(&rd); // Drop packet
175
}
176
177
return true;
178
}
179
180
int8_t BL_Network::ethernetif_init(struct netif *netif)
181
{
182
netif->state = NULL;
183
netif->name[0] = 'm';
184
netif->name[1] = 's';
185
netif->output = etharp_output;
186
netif->linkoutput = low_level_output;
187
188
/* set MAC hardware address length */
189
netif->hwaddr_len = ETHARP_HWADDR_LEN;
190
191
/* maximum transfer unit */
192
netif->mtu = LWIP_NETIF_MTU;
193
194
/* device capabilities */
195
netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP;
196
197
#if LWIP_IGMP
198
// also enable multicast
199
netif->flags |= NETIF_FLAG_IGMP;
200
#endif
201
202
return ERR_OK;
203
}
204
205
/*
206
networking thread
207
*/
208
void BL_Network::net_thread()
209
{
210
/* start tcpip thread */
211
tcpip_init(NULL, NULL);
212
213
thread_sleep_ms(100);
214
215
AP_Networking::convert_str_to_macaddr(AP_NETWORKING_BOOTLOADER_DEFAULT_MAC_ADDR, thisif->hwaddr);
216
217
ip4_addr_t ip, gateway, netmask;
218
if (addr.ip == 0) {
219
// no IP from AP_Periph, use defaults
220
ip.addr = htonl(SocketAPM::inet_str_to_addr(AP_NETWORKING_BOOTLOADER_DEFAULT_IP));
221
gateway.addr = htonl(SocketAPM::inet_str_to_addr(AP_NETWORKING_BOOTLOADER_DEFAULT_GATEWAY));
222
netmask.addr = htonl(SocketAPM::inet_str_to_addr(AP_NETWORKING_BOOTLOADER_DEFAULT_NETMASK));
223
} else {
224
// use addresses from AP_Periph
225
ip.addr = htonl(addr.ip);
226
netmask.addr = htonl(addr.netmask);
227
gateway.addr = htonl(addr.gateway);
228
}
229
230
const MACConfig mac_config = {thisif->hwaddr};
231
macStart(&ETHD1, &mac_config);
232
233
/* Add interface. */
234
235
auto result = netifapi_netif_add(thisif, &ip, &netmask, &gateway, NULL, ethernetif_init, tcpip_input);
236
if (result != ERR_OK) {
237
AP_HAL::panic("Failed to initialise netif");
238
}
239
240
netifapi_netif_set_default(thisif);
241
netifapi_netif_set_up(thisif);
242
243
/* Setup event sources.*/
244
event_timer_t evt;
245
event_listener_t el0, el1;
246
247
evtObjectInit(&evt, LWIP_LINK_POLL_INTERVAL);
248
evtStart(&evt);
249
chEvtRegisterMask(&evt.et_es, &el0, PERIODIC_TIMER_ID);
250
chEvtRegisterMaskWithFlags(macGetEventSource(&ETHD1), &el1,
251
FRAME_RECEIVED_ID, MAC_FLAGS_RX);
252
chEvtAddEvents(PERIODIC_TIMER_ID | FRAME_RECEIVED_ID);
253
254
while (true) {
255
eventmask_t mask = chEvtWaitAny(ALL_EVENTS);
256
if (mask & PERIODIC_TIMER_ID) {
257
bool current_link_status = macPollLinkStatus(&ETHD1);
258
if (current_link_status != netif_is_link_up(thisif)) {
259
if (current_link_status) {
260
tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_up, thisif, 0);
261
tcpip_callback_with_block(link_up_cb, this, 0);
262
}
263
else {
264
tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_down, thisif, 0);
265
tcpip_callback_with_block(link_down_cb, this, 0);
266
}
267
}
268
}
269
270
if (mask & FRAME_RECEIVED_ID) {
271
struct pbuf *p;
272
while (low_level_input(thisif, &p)) {
273
if (p != NULL) {
274
struct eth_hdr *ethhdr = (struct eth_hdr *)p->payload;
275
switch (htons(ethhdr->type)) {
276
/* IP or ARP packet? */
277
case ETHTYPE_IP:
278
case ETHTYPE_ARP:
279
/* full packet send to tcpip_thread to process */
280
if (thisif->input(p, thisif) == ERR_OK) {
281
break;
282
}
283
/* Falls through */
284
default:
285
pbuf_free(p);
286
}
287
}
288
}
289
}
290
}
291
}
292
293
void BL_Network::net_thread_trampoline(void *ctx)
294
{
295
auto *net = (BL_Network *)ctx;
296
net->net_thread();
297
}
298
299
void BL_Network::web_server_trampoline(void *ctx)
300
{
301
auto *net = (BL_Network *)ctx;
302
net->web_server();
303
}
304
305
#define STR_HELPER(x) #x
306
#define STR(x) STR_HELPER(x)
307
308
BL_Network::web_var BL_Network::variables[] = {
309
{ "BOARD_NAME", CHIBIOS_BOARD_NAME },
310
{ "BOARD_ID", STR(APJ_BOARD_ID) },
311
{ "FLASH_SIZE", STR(BOARD_FLASH_SIZE) },
312
};
313
314
/*
315
substitute variables of the form {VARNAME}
316
*/
317
char *BL_Network::substitute_vars(const char *str, uint32_t size)
318
{
319
// assume 1024 is enough room for new variables
320
char *result = (char *)malloc(strlen(str) + 1024);
321
if (result == nullptr) {
322
return nullptr;
323
}
324
char *p = result;
325
const char *str0 = str;
326
while (*str && str-str0<size) {
327
if (*str != '{') {
328
*p++ = *str++;
329
continue;
330
}
331
char *q = strchr(str+1, '}');
332
if (q == nullptr) {
333
*p++ = *str++;
334
continue;
335
}
336
const uint32_t len = (q - str)-1;
337
bool found = false;
338
for (auto &v : variables) {
339
if (strlen(v.name) == len && strncmp(v.name, str+1, len) == 0) {
340
found = true;
341
strcpy(p, v.value);
342
p += strlen(v.value);
343
str = q+1;
344
break;
345
}
346
}
347
if (found) {
348
continue;
349
}
350
*p++ = *str++;
351
}
352
*p = '\0';
353
return result;
354
}
355
356
/*
357
read HTTP headers, returing as a single string
358
*/
359
char *BL_Network::read_headers(SocketAPM *sock)
360
{
361
char *ret = (char *)malloc(1024);
362
char *p = ret;
363
while (true) {
364
char c;
365
auto n = sock->recv(&c, 1, 100);
366
if (n != 1) {
367
break;
368
}
369
*p++ = c;
370
if (p-ret >= 4 && strcmp(p-4, "\r\n\r\n") == 0) {
371
break;
372
}
373
}
374
return ret;
375
}
376
377
/*
378
handle an incoming HTTP POST request
379
*/
380
void BL_Network::handle_post(SocketAPM *sock, uint32_t content_length)
381
{
382
/*
383
skip over form boundary. We don't care about the filename as we
384
only support one file
385
*/
386
uint8_t state = 0;
387
while (true) {
388
char c;
389
if (sock->recv(&c, 1, 100) != 1) {
390
return;
391
}
392
content_length--;
393
// absorb up to \r\n\r\n
394
if (c == '\r') {
395
if (state == 2) {
396
state = 3;
397
} else {
398
state = 1;
399
}
400
} else if (c == '\n') {
401
if (state == 1 || state == 3) {
402
state++;
403
} else {
404
state = 0;
405
}
406
if (state == 4) {
407
break;
408
}
409
} else {
410
state = 0;
411
}
412
}
413
/*
414
erase all of flash
415
*/
416
status_printf("Erasing ...");
417
flash_set_keep_unlocked(true);
418
uint32_t sec=0;
419
while (flash_func_sector_size(sec) != 0 &&
420
flash_func_erase_sector(sec)) {
421
thread_sleep_ms(10);
422
sec++;
423
if (stm32_flash_getpageaddr(sec) - stm32_flash_getpageaddr(0) >= content_length) {
424
break;
425
}
426
}
427
/*
428
receive file and write to flash
429
*/
430
uint32_t buf[128];
431
uint32_t ofs = 0;
432
433
// must be multiple of 4
434
content_length &= ~3;
435
436
const uint32_t max_ofs = MIN(BOARD_FLASH_SIZE*1024, content_length);
437
uint8_t last_pct = 0;
438
while (ofs < max_ofs) {
439
const uint32_t needed = MIN(sizeof(buf), max_ofs-ofs);
440
auto n = sock->recv((void*)buf, needed, 10000);
441
if (n <= 0) {
442
break;
443
}
444
// we need a whole number of words
445
if (n % 4 != 0 && n < needed) {
446
auto n2 = sock->recv(((uint8_t*)buf)+n, 4 - n%4, 10000);
447
if (n2 > 0) {
448
n += n2;
449
}
450
}
451
flash_write_buffer(ofs, buf, n/4);
452
ofs += n;
453
uint8_t pct = ofs*100/max_ofs;
454
if (pct % 10 == 0 && last_pct != pct) {
455
last_pct = pct;
456
status_printf("Flashing %u%%", unsigned(pct));
457
}
458
}
459
if (ofs % 32 != 0) {
460
// pad to 32 bytes
461
memset(buf, 0xff, sizeof(buf));
462
flash_write_buffer(ofs, buf, (32 - ofs%32)/4);
463
}
464
flash_write_flush();
465
flash_set_keep_unlocked(false);
466
const auto ok = check_good_firmware();
467
if (ok == check_fw_result_t::CHECK_FW_OK) {
468
need_launch = true;
469
status_printf("Flash done: OK");
470
const char *str = "<html><head><meta http-equiv=\"refresh\" content=\"4; url=/\"></head><body>Flash OK, booting</body></html>";
471
sock->send(str, strlen(str));
472
} else {
473
status_printf("Flash done: ERR:%u", unsigned(ok));
474
}
475
}
476
477
/*
478
handle an incoming HTTP request
479
*/
480
void BL_Network::handle_request(SocketAPM *sock)
481
{
482
/*
483
read HTTP headers
484
*/
485
char *headers = read_headers(sock);
486
487
const char *header = "HTTP/1.1 200 OK\r\n"
488
"Content-Type: text/html\r\n"
489
"Connection: close\r\n"
490
"\r\n";
491
sock->send(header, strlen(header));
492
493
if (strncmp(headers, "POST / ", 7) == 0) {
494
const char *clen1 = "\r\nContent-Length:";
495
const char *clen2 = "\r\ncontent-length:";
496
const char *p = strstr(headers, clen1);
497
if (p == nullptr) {
498
p = strstr(headers, clen2);
499
}
500
if (p != nullptr) {
501
p += strlen(clen1);
502
const uint32_t content_length = atoi(p);
503
handle_post(sock, content_length);
504
delete headers;
505
delete sock;
506
return;
507
}
508
}
509
510
/*
511
check for async status
512
*/
513
const char *get_status = "GET /bootloader_status.html";
514
if (strncmp(headers, get_status, strlen(get_status)) == 0) {
515
{
516
WITH_SEMAPHORE(status_mtx);
517
sock->send(bl_status, strlen(bl_status));
518
}
519
delete headers;
520
delete sock;
521
return;
522
}
523
524
const char *get_reboot = "GET /REBOOT";
525
if (strncmp(headers, get_reboot, strlen(get_reboot)) == 0) {
526
need_reboot = true;
527
}
528
529
uint32_t size = 0;
530
const auto *msg = AP_ROMFS::find_decompress("index.html", size);
531
if (need_reboot) {
532
const char *str = "<html><head><meta http-equiv=\"refresh\" content=\"2; url=/\"></head></html>";
533
sock->send(str, strlen(str));
534
} else {
535
char *msg2 = substitute_vars((const char *)msg, size);
536
sock->send(msg2, strlen(msg2));
537
delete msg2;
538
}
539
delete headers;
540
delete sock;
541
AP_ROMFS::free(msg);
542
}
543
544
struct req_context {
545
BL_Network *driver;
546
SocketAPM *sock;
547
};
548
549
void BL_Network::net_request_trampoline(void *ctx)
550
{
551
auto *req = (req_context *)ctx;
552
req->driver->handle_request(req->sock);
553
554
auto *driver = req->driver;
555
auto *thd = chThdGetSelfX();
556
delete req;
557
558
WITH_SEMAPHORE(driver->web_delete_mtx);
559
thd->delete_next = driver->web_delete_list;
560
driver->web_delete_list = thd;
561
}
562
563
/*
564
web server thread
565
*/
566
void BL_Network::web_server(void)
567
{
568
auto *listen_socket = NEW_NOTHROW SocketAPM(0);
569
listen_socket->bind("0.0.0.0", 80);
570
listen_socket->listen(20);
571
572
while (true) {
573
auto *sock = listen_socket->accept(20);
574
if (need_reboot) {
575
need_reboot = false;
576
NVIC_SystemReset();
577
}
578
if (need_launch) {
579
need_launch = false;
580
thread_sleep_ms(1000);
581
jump_to_app();
582
}
583
if (sock == nullptr) {
584
continue;
585
}
586
// a new thread for each connection to allow for AJAX
587
auto *req = NEW_NOTHROW req_context;
588
req->driver = this;
589
req->sock = sock;
590
thread_create_alloc(THD_WORKING_AREA_SIZE(2048),
591
"web_request",
592
60,
593
net_request_trampoline,
594
req);
595
596
// cleanup any finished threads
597
WITH_SEMAPHORE(web_delete_mtx);
598
while (web_delete_list != nullptr) {
599
auto *thd = web_delete_list;
600
web_delete_list = thd->delete_next;
601
chThdRelease(thd);
602
}
603
}
604
}
605
606
/*
607
initialise bootloader networking
608
*/
609
void BL_Network::init()
610
{
611
AP_Networking_ChibiOS::allocate_buffers();
612
613
macInit();
614
615
thisif = NEW_NOTHROW netif;
616
617
net_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(2048),
618
"network",
619
60,
620
net_thread_trampoline,
621
this);
622
623
thread_create_alloc(THD_WORKING_AREA_SIZE(2048),
624
"web_server",
625
60,
626
web_server_trampoline,
627
this);
628
}
629
630
/*
631
save IP address from AP_Periph
632
*/
633
void BL_Network::save_comms_ip(void)
634
{
635
struct app_bootloader_comms *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
636
if (comms->magic == APP_BOOTLOADER_COMMS_MAGIC && comms->ip != 0) {
637
addr.ip = comms->ip;
638
addr.netmask = comms->netmask;
639
addr.gateway = comms->gateway;
640
}
641
}
642
643
/*
644
update status message
645
*/
646
void BL_Network::status_printf(const char *fmt, ...)
647
{
648
WITH_SEMAPHORE(status_mtx);
649
va_list ap;
650
va_start(ap, fmt);
651
vsnprintf(bl_status, sizeof(bl_status), fmt, ap);
652
va_end(ap);
653
can_printf("%s", bl_status);
654
}
655
656
#endif // AP_BOOTLOADER_NETWORK_ENABLED
657
658
659