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/libraries/AP_Filesystem/AP_Filesystem_Param.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
ArduPilot filesystem interface for parameters
17
*/
18
19
#include "AP_Filesystem_config.h"
20
21
#if AP_FILESYSTEM_PARAM_ENABLED
22
23
#include "AP_Filesystem.h"
24
#include "AP_Filesystem_Param.h"
25
#include <AP_Param/AP_Param.h>
26
#include <AP_Math/AP_Math.h>
27
#include <ctype.h>
28
29
#define PACKED_NAME "param.pck"
30
31
extern const AP_HAL::HAL& hal;
32
33
// QURT HAL already has a declaration of errno in errno.h
34
#if CONFIG_HAL_BOARD != HAL_BOARD_QURT
35
extern int errno;
36
#endif
37
38
int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_path)
39
{
40
if (!check_file_name(fname)) {
41
errno = ENOENT;
42
return -1;
43
}
44
bool read_only = ((flags & O_ACCMODE) == O_RDONLY);
45
uint8_t idx;
46
for (idx=0; idx<max_open_file; idx++) {
47
if (!file[idx].open) {
48
break;
49
}
50
}
51
if (idx == max_open_file) {
52
errno = ENFILE;
53
return -1;
54
}
55
struct rfile &r = file[idx];
56
if (read_only) {
57
r.cursors = NEW_NOTHROW cursor[num_cursors];
58
if (r.cursors == nullptr) {
59
errno = ENOMEM;
60
return -1;
61
}
62
}
63
r.file_ofs = 0;
64
r.open = true;
65
r.with_defaults = false;
66
r.start = 0;
67
r.count = 0;
68
r.read_size = 0;
69
r.file_size = 0;
70
r.writebuf = nullptr;
71
if (!read_only) {
72
// setup for upload
73
r.writebuf = NEW_NOTHROW ExpandingString();
74
if (r.writebuf == nullptr) {
75
close(idx);
76
errno = ENOMEM;
77
return -1;
78
}
79
}
80
81
/*
82
allow for URI style arguments param.pck?start=N&count=C
83
*/
84
const char *c = strchr(fname, '?');
85
while (c && *c) {
86
c++;
87
if (strncmp(c, "start=", 6) == 0) {
88
uint32_t v = strtoul(c+6, nullptr, 10);
89
if (v >= UINT16_MAX) {
90
goto failed;
91
}
92
r.start = v;
93
c += 6;
94
c = strchr(c, '&');
95
continue;
96
}
97
if (strncmp(c, "count=", 6) == 0) {
98
uint32_t v = strtoul(c+6, nullptr, 10);
99
if (v >= UINT16_MAX) {
100
goto failed;
101
}
102
r.count = v;
103
c += 6;
104
c = strchr(c, '&');
105
continue;
106
}
107
#if AP_PARAM_DEFAULTS_ENABLED
108
if (strncmp(c, "withdefaults=", 13) == 0) {
109
uint32_t v = strtoul(c+13, nullptr, 10);
110
if (v > 1) {
111
goto failed;
112
}
113
r.with_defaults = v == 1;
114
c += 13;
115
c = strchr(c, '&');
116
continue;
117
}
118
#endif
119
}
120
121
return idx;
122
123
failed:
124
delete [] r.cursors;
125
r.open = false;
126
errno = EINVAL;
127
return -1;
128
}
129
130
int AP_Filesystem_Param::close(int fd)
131
{
132
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
133
errno = EBADF;
134
return -1;
135
}
136
struct rfile &r = file[fd];
137
int ret = 0;
138
if (r.writebuf != nullptr && !finish_upload(r)) {
139
errno = EINVAL;
140
ret = -1;
141
}
142
r.open = false;
143
delete [] r.cursors;
144
r.cursors = nullptr;
145
delete r.writebuf;
146
r.writebuf = nullptr;
147
return ret;
148
}
149
150
/*
151
packed format:
152
file header:
153
uint16_t magic = 0x671b or 0x671c for included default values
154
uint16_t num_params
155
uint16_t total_params
156
157
per-parameter:
158
159
uint8_t type:4; // AP_Param type NONE=0, INT8=1, INT16=2, INT32=3, FLOAT=4
160
uint8_t flags:4; // bit 0: includes default value for this param
161
uint8_t common_len:4; // number of name bytes in common with previous entry, 0..15
162
uint8_t name_len:4; // non-common length of param name -1 (0..15)
163
uint8_t name[name_len]; // name
164
uint8_t data[]; // value, length given by variable type, data length doubled if default is included
165
166
Any leading zero bytes after the header should be discarded as pad
167
bytes. Pad bytes are used to ensure that a parameter data[] field
168
does not cross a read packet boundary
169
*/
170
171
/*
172
pack a single parameter. The buffer must be at least of size max_pack_len
173
*/
174
uint8_t AP_Filesystem_Param::pack_param(const struct rfile &r, struct cursor &c, uint8_t *buf)
175
{
176
char name[AP_MAX_NAME_SIZE+1];
177
name[AP_MAX_NAME_SIZE] = 0;
178
enum ap_var_type ptype;
179
AP_Param *ap;
180
float default_val;
181
182
if (c.token_ofs == 0) {
183
c.idx = 0;
184
ap = AP_Param::first(&c.token, &ptype, &default_val);
185
uint16_t idx = 0;
186
while (idx < r.start && ap) {
187
ap = AP_Param::next_scalar(&c.token, &ptype, &default_val);
188
idx++;
189
}
190
} else {
191
c.idx++;
192
ap = AP_Param::next_scalar(&c.token, &ptype, &default_val);
193
}
194
if (ap == nullptr || (r.count && c.idx >= r.count)) {
195
if (r.count == 0 && c.idx != AP_Param::count_parameters()) {
196
// the parameter count is incorrect, invalidate so a
197
// repeated param download avoids an error
198
AP_Param::invalidate_count();
199
}
200
return 0;
201
}
202
ap->copy_name_token(c.token, name, AP_MAX_NAME_SIZE, true);
203
204
uint8_t common_len = 0;
205
const char *last_name = c.last_name;
206
const char *pname = name;
207
while (*pname == *last_name && *pname) {
208
common_len++;
209
pname++;
210
last_name++;
211
}
212
uint8_t name_len = strlen(pname);
213
if (name_len == 0) {
214
name_len = 1;
215
common_len--;
216
pname--;
217
}
218
#if AP_PARAM_DEFAULTS_ENABLED
219
const bool add_default = r.with_defaults && !is_equal(ap->cast_to_float(ptype), default_val);
220
#else
221
const bool add_default = false;
222
#endif
223
const uint8_t type_len = AP_Param::type_size(ptype);
224
uint8_t packed_len = type_len + name_len + 2 + (add_default ? type_len : 0);
225
const uint8_t flags = add_default;
226
227
/*
228
see if we need to add padding to ensure that a data field never
229
crosses a block boundary. This ensures that re-reading a block
230
won't get a corrupt value for a parameter
231
*/
232
if (type_len > 1) {
233
const uint32_t ofs = c.token_ofs + sizeof(struct header) + packed_len;
234
const uint32_t ofs_mod = ofs % r.read_size;
235
if (ofs_mod > 0 && ofs_mod < type_len) {
236
const uint8_t pad = type_len - ofs_mod;
237
memset(buf, 0, pad);
238
buf += pad;
239
packed_len += pad;
240
}
241
}
242
243
buf[0] = uint8_t(ptype) | (flags<<4);
244
buf[1] = common_len | ((name_len-1)<<4);
245
memcpy(&buf[2], pname, name_len);
246
memcpy(&buf[2+name_len], ap, type_len);
247
#if AP_PARAM_DEFAULTS_ENABLED
248
if (add_default) {
249
switch (ptype) {
250
case AP_PARAM_NONE:
251
case AP_PARAM_GROUP:
252
// should never happen...
253
break;
254
case AP_PARAM_INT8: {
255
const int32_t int8_default = default_val;
256
memcpy(&buf[2+name_len+type_len], &int8_default, type_len);
257
break;
258
}
259
case AP_PARAM_INT16: {
260
const int16_t int16_default = default_val;
261
memcpy(&buf[2+name_len+type_len], &int16_default, type_len);
262
break;
263
}
264
case AP_PARAM_INT32: {
265
const int32_t int32_default = default_val;
266
memcpy(&buf[2+name_len+type_len], &int32_default, type_len);
267
break;
268
}
269
case AP_PARAM_FLOAT:
270
case AP_PARAM_VECTOR3F: {
271
memcpy(&buf[2+name_len+type_len], &default_val, type_len);
272
break;
273
}
274
}
275
}
276
#endif
277
278
strcpy(c.last_name, name);
279
280
return packed_len;
281
}
282
283
/*
284
seek the token to match file offset
285
*/
286
bool AP_Filesystem_Param::token_seek(const struct rfile &r, const uint32_t data_ofs, struct cursor &c)
287
{
288
if (data_ofs == 0) {
289
memset(&c, 0, sizeof(c));
290
return true;
291
}
292
if (c.token_ofs > data_ofs) {
293
memset(&c, 0, sizeof(c));
294
}
295
296
if (c.trailer_len > 0) {
297
uint8_t n = MIN(c.trailer_len, data_ofs - c.token_ofs);
298
if (n != c.trailer_len) {
299
memmove(&c.trailer[0], &c.trailer[n], c.trailer_len - n);
300
}
301
c.trailer_len -= n;
302
c.token_ofs += n;
303
}
304
305
while (data_ofs != c.token_ofs) {
306
uint32_t available = data_ofs - c.token_ofs;
307
uint8_t tbuf[max_pack_len];
308
uint8_t len = pack_param(r, c, tbuf);
309
if (len == 0) {
310
// no more parameters
311
break;
312
}
313
uint8_t n = MIN(len, available);
314
if (len > available) {
315
c.trailer_len = len - available;
316
memcpy(c.trailer, &tbuf[n], c.trailer_len);
317
}
318
c.token_ofs += n;
319
}
320
return data_ofs == c.token_ofs;
321
}
322
323
int32_t AP_Filesystem_Param::read(int fd, void *buf, uint32_t count)
324
{
325
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
326
errno = EBADF;
327
return -1;
328
}
329
330
struct rfile &r = file[fd];
331
if (r.writebuf != nullptr) {
332
// no read on upload
333
errno = EINVAL;
334
return -1;
335
}
336
size_t header_total = 0;
337
338
/*
339
we only allow for a single read size. This ensures that pad
340
bytes placed to avoid a data value crossing a block boundary in
341
the ftp protocol do not change when filling in lost packets
342
*/
343
if (r.read_size == 0 && count > 0) {
344
r.read_size = count;
345
}
346
if (r.read_size != 0 && r.read_size != count) {
347
errno = EINVAL;
348
return -1;
349
}
350
351
if (r.file_size != 0) {
352
// ensure we don't try to read past EOF
353
if (r.file_ofs > r.file_size) {
354
count = 0;
355
} else {
356
count = MIN(count, r.file_size - r.file_ofs);
357
}
358
}
359
360
if (r.file_ofs < sizeof(struct header)) {
361
struct header hdr;
362
hdr.total_params = AP_Param::count_parameters();
363
if (hdr.total_params <= r.start) {
364
errno = EINVAL;
365
return -1;
366
}
367
hdr.num_params = hdr.total_params - r.start;
368
if (r.count > 0 && hdr.num_params > r.count) {
369
hdr.num_params = r.count;
370
}
371
uint8_t n = MIN(sizeof(hdr) - r.file_ofs, count);
372
if (r.with_defaults) {
373
hdr.magic = pmagic_with_default;
374
}
375
const uint8_t *b = (const uint8_t *)&hdr;
376
memcpy(buf, &b[r.file_ofs], n);
377
count -= n;
378
header_total += n;
379
r.file_ofs += n;
380
buf = (void *)(n + (const uint8_t *)buf);
381
if (count == 0) {
382
return header_total;
383
}
384
}
385
386
uint32_t data_ofs = r.file_ofs - sizeof(struct header);
387
uint8_t best_i = 0;
388
uint32_t best_ofs = r.cursors[0].token_ofs;
389
size_t total = 0;
390
391
// find the first cursor that is positioned after the file offset
392
for (uint8_t i=1; i<num_cursors; i++) {
393
struct cursor &c = r.cursors[i];
394
if (c.token_ofs >= data_ofs && c.token_ofs < best_ofs) {
395
best_i = i;
396
best_ofs = c.token_ofs;
397
}
398
}
399
struct cursor &c = r.cursors[best_i];
400
401
if (data_ofs != c.token_ofs) {
402
if (!token_seek(r, data_ofs, c)) {
403
// must be EOF
404
return header_total;
405
}
406
}
407
if (count == 0) {
408
return header_total;
409
}
410
uint8_t *ubuf = (uint8_t *)buf;
411
412
if (c.trailer_len > 0) {
413
uint8_t n = MIN(c.trailer_len, count);
414
memcpy(ubuf, c.trailer, n);
415
count -= n;
416
ubuf += n;
417
if (n != c.trailer_len) {
418
memmove(&c.trailer[0], &c.trailer[n], c.trailer_len - n);
419
}
420
c.trailer_len -= n;
421
total += n;
422
c.token_ofs += n;
423
}
424
425
while (count > 0) {
426
uint8_t tbuf[max_pack_len];
427
uint8_t len = pack_param(r, c, tbuf);
428
if (len == 0) {
429
// no more params, use this to trigger EOF in later reads
430
const uint32_t size = r.file_ofs + total;
431
if (r.file_size == 0) {
432
r.file_size = size;
433
} else {
434
r.file_size = MIN(size, r.file_size);
435
}
436
break;
437
}
438
uint8_t n = MIN(len, count);
439
if (len > count) {
440
c.trailer_len = len - count;
441
memcpy(c.trailer, &tbuf[count], c.trailer_len);
442
}
443
memcpy(ubuf, tbuf, n);
444
count -= n;
445
ubuf += n;
446
total += n;
447
c.token_ofs += n;
448
}
449
r.file_ofs += total;
450
return total + header_total;
451
}
452
453
int32_t AP_Filesystem_Param::lseek(int fd, int32_t offset, int seek_from)
454
{
455
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
456
errno = EBADF;
457
return -1;
458
}
459
struct rfile &r = file[fd];
460
switch (seek_from) {
461
case SEEK_SET:
462
r.file_ofs = offset;
463
break;
464
case SEEK_CUR:
465
r.file_ofs += offset;
466
break;
467
case SEEK_END:
468
errno = EINVAL;
469
return -1;
470
}
471
return r.file_ofs;
472
}
473
474
int AP_Filesystem_Param::stat(const char *name, struct stat *stbuf)
475
{
476
if (!check_file_name(name)) {
477
errno = ENOENT;
478
return -1;
479
}
480
memset(stbuf, 0, sizeof(*stbuf));
481
// give size estimation to avoid needing to scan entire file
482
stbuf->st_size = AP_Param::count_parameters() * 12;
483
return 0;
484
}
485
486
/*
487
check for the right file name
488
*/
489
bool AP_Filesystem_Param::check_file_name(const char *name)
490
{
491
const uint8_t packed_len = strlen(PACKED_NAME);
492
if (strncmp(name, PACKED_NAME, packed_len) == 0 &&
493
(name[packed_len] == 0 || name[packed_len] == '?')) {
494
return true;
495
}
496
return false;
497
}
498
499
/*
500
support param upload
501
*/
502
int32_t AP_Filesystem_Param::write(int fd, const void *buf, uint32_t count)
503
{
504
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
505
errno = EBADF;
506
return -1;
507
}
508
struct rfile &r = file[fd];
509
if (r.writebuf == nullptr) {
510
errno = EBADF;
511
return -1;
512
}
513
struct header hdr;
514
if (r.file_ofs == 0 && count >= sizeof(hdr)) {
515
// pre-expand the buffer to the full size when we get the header
516
memcpy(&hdr, buf, sizeof(hdr));
517
if (hdr.magic == pmagic) {
518
const uint32_t flen = hdr.total_params;
519
if (flen > r.writebuf->get_length()) {
520
if (!r.writebuf->append(nullptr, flen - r.writebuf->get_length())) {
521
// not enough memory
522
return -1;
523
}
524
}
525
}
526
}
527
if (r.file_ofs + count > r.writebuf->get_length()) {
528
if (!r.writebuf->append(nullptr, r.file_ofs + count - r.writebuf->get_length())) {
529
return -1;
530
}
531
}
532
uint8_t *b = (uint8_t *)r.writebuf->get_writeable_string();
533
memcpy(&b[r.file_ofs], buf, count);
534
r.file_ofs += count;
535
return count;
536
}
537
538
/*
539
parse incoming parameters
540
*/
541
bool AP_Filesystem_Param::param_upload_parse(const rfile &r, bool &need_retry)
542
{
543
need_retry = false;
544
545
const uint8_t *b = (const uint8_t *)r.writebuf->get_string();
546
uint32_t length = r.writebuf->get_length();
547
struct header hdr;
548
if (length < sizeof(hdr)) {
549
return false;
550
}
551
memcpy(&hdr, b, sizeof(hdr));
552
if (hdr.magic != pmagic) {
553
return false;
554
}
555
if (length != hdr.total_params) {
556
return false;
557
}
558
b += sizeof(hdr);
559
560
char last_name[17] {};
561
562
for (uint16_t i=0; i<hdr.num_params; i++) {
563
enum ap_var_type ptype = (enum ap_var_type)(b[0]&0x0F);
564
uint8_t flags = (enum ap_var_type)(b[0]>>4);
565
if (flags != 0) {
566
return false;
567
}
568
uint8_t common_len = b[1]&0xF;
569
uint8_t name_len = (b[1]>>4)+1;
570
if (common_len + name_len > 16) {
571
return false;
572
}
573
char name[17];
574
memcpy(name, last_name, common_len);
575
memcpy(&name[common_len], &b[2], name_len);
576
name[common_len+name_len] = 0;
577
578
memcpy(last_name, name, sizeof(name));
579
enum ap_var_type ptype2 = AP_PARAM_NONE;
580
uint16_t flags2;
581
582
b += 2 + name_len;
583
584
AP_Param *p = AP_Param::find(name, &ptype2, &flags2);
585
if (p == nullptr) {
586
if (ptype == AP_PARAM_INT8) {
587
b++;
588
} else if (ptype == AP_PARAM_INT16) {
589
b += 2;
590
} else {
591
b += 4;
592
}
593
continue;
594
}
595
596
/*
597
if we are enabling a subsystem we need a small delay between
598
parameters to allow main thread to perform any allocation of
599
backends
600
*/
601
bool need_delay = ((flags2 & AP_PARAM_FLAG_ENABLE) != 0 &&
602
ptype2 == AP_PARAM_INT8 &&
603
((AP_Int8 *)p)->get() == 0);
604
605
if (ptype == ptype2 && ptype == AP_PARAM_INT32) {
606
// special handling of int32_t to preserve all bits
607
int32_t v;
608
memcpy(&v, b, sizeof(v));
609
((AP_Int32 *)p)->set(v);
610
b += 4;
611
} else if (ptype == AP_PARAM_INT8) {
612
if (need_delay && b[0] == 0) {
613
need_delay = false;
614
}
615
p->set_float((int8_t)b[0], ptype2);
616
b += 1;
617
} else if (ptype == AP_PARAM_INT16) {
618
int16_t v;
619
memcpy(&v, b, sizeof(v));
620
p->set_float(float(v), ptype2);
621
b += 2;
622
} else if (ptype == AP_PARAM_INT32) {
623
int32_t v;
624
memcpy(&v, b, sizeof(v));
625
p->set_float(float(v), ptype2);
626
b += 4;
627
} else if (ptype == AP_PARAM_FLOAT) {
628
float v;
629
memcpy(&v, b, sizeof(v));
630
p->set_float(v, ptype2);
631
b += 4;
632
}
633
634
p->save_sync(false, false);
635
636
if (need_delay) {
637
// let main thread have some time to init backends
638
need_retry = true;
639
hal.scheduler->delay(100);
640
}
641
}
642
return true;
643
}
644
645
646
/*
647
parse incoming parameters
648
*/
649
bool AP_Filesystem_Param::finish_upload(const rfile &r)
650
{
651
uint8_t loops = 0;
652
while (loops++ < 4) {
653
bool need_retry;
654
if (!param_upload_parse(r, need_retry)) {
655
return false;
656
}
657
if (!need_retry) {
658
break;
659
}
660
}
661
return true;
662
}
663
664
#endif // AP_FILESYSTEM_PARAM_ENABLED
665
666