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_Mission.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 mission/fence/rally
17
*/
18
19
#include "AP_Filesystem_config.h"
20
21
#if AP_FILESYSTEM_MISSION_ENABLED
22
23
#include "AP_Filesystem.h"
24
#include "AP_Filesystem_Mission.h"
25
#include <AP_Mission/AP_Mission.h>
26
#include <AC_Fence/AC_Fence.h>
27
#include <AP_Rally/AP_Rally.h>
28
#include <GCS_MAVLink/MissionItemProtocol_Rally.h>
29
#include <GCS_MAVLink/MissionItemProtocol_Fence.h>
30
#include <GCS_MAVLink/GCS.h>
31
32
extern const AP_HAL::HAL& hal;
33
34
// QURT HAL already has a declaration of errno in errno.h
35
#if CONFIG_HAL_BOARD != HAL_BOARD_QURT
36
extern int errno;
37
#endif
38
39
#define IDLE_TIMEOUT_MS 30000
40
41
int AP_Filesystem_Mission::open(const char *fname, int flags, bool allow_absolute_paths)
42
{
43
enum MAV_MISSION_TYPE mtype;
44
45
if (!check_file_name(fname, mtype)) {
46
errno = ENOENT;
47
return -1;
48
}
49
uint8_t idx;
50
bool readonly = ((flags & O_ACCMODE) == O_RDONLY);
51
uint32_t now = AP_HAL::millis();
52
for (idx=0; idx<max_open_file; idx++) {
53
if (now - file[idx].last_op_ms > IDLE_TIMEOUT_MS) {
54
file[idx].open = false;
55
delete file[idx].writebuf;
56
file[idx].writebuf = nullptr;
57
}
58
if (!readonly && file[idx].writebuf != nullptr) {
59
// only one upload at a time
60
return -1;
61
}
62
if (!file[idx].open) {
63
break;
64
}
65
}
66
if (idx == max_open_file) {
67
errno = ENFILE;
68
return -1;
69
}
70
struct rfile &r = file[idx];
71
r.file_ofs = 0;
72
r.open = true;
73
r.mtype = mtype;
74
r.num_items = get_num_items(r.mtype);
75
if (!readonly) {
76
// setup for upload
77
r.writebuf = NEW_NOTHROW ExpandingString();
78
} else {
79
r.writebuf = nullptr;
80
}
81
r.last_op_ms = now;
82
83
return idx;
84
}
85
86
int AP_Filesystem_Mission::close(int fd)
87
{
88
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
89
errno = EBADF;
90
return -1;
91
}
92
struct rfile &r = file[fd];
93
r.open = false;
94
if (r.writebuf != nullptr) {
95
bool ok = finish_upload(r);
96
delete r.writebuf;
97
r.writebuf = nullptr;
98
if (!ok) {
99
errno = EINVAL;
100
return -1;
101
}
102
}
103
return 0;
104
}
105
106
/*
107
packed format:
108
file header:
109
uint16_t magic = 0x671b
110
uint16_t data_type MAV_MISSION_TYPE_*
111
uint32_t total_items
112
113
per-entry is mavlink packed item
114
*/
115
116
/*
117
read from file handle
118
*/
119
int32_t AP_Filesystem_Mission::read(int fd, void *buf, uint32_t count)
120
{
121
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
122
errno = EBADF;
123
return -1;
124
}
125
126
struct rfile &r = file[fd];
127
128
if (r.writebuf != nullptr) {
129
errno = EBADF;
130
return -1;
131
}
132
133
r.last_op_ms = AP_HAL::millis();
134
135
size_t header_total = 0;
136
uint8_t *ubuf = (uint8_t *)buf;
137
138
if (r.file_ofs < sizeof(struct header)) {
139
struct header hdr {};
140
hdr.data_type = uint16_t(r.mtype);
141
hdr.num_items = r.num_items;
142
uint8_t n = MIN(sizeof(hdr) - r.file_ofs, count);
143
const uint8_t *b = (const uint8_t *)&hdr;
144
memcpy(ubuf, &b[r.file_ofs], n);
145
count -= n;
146
header_total += n;
147
r.file_ofs += n;
148
ubuf += n;
149
if (count == 0) {
150
return header_total;
151
}
152
}
153
154
uint32_t data_ofs = r.file_ofs - sizeof(struct header);
155
mavlink_mission_item_int_t item {};
156
const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;
157
uint32_t item_ofs = data_ofs % item_size;
158
uint32_t total = 0;
159
160
while (count > 0) {
161
uint32_t item_idx = data_ofs / item_size;
162
163
const uint8_t *ibuf = (const uint8_t *)&item;
164
if (!get_item(item_idx, r.mtype, item)) {
165
break;
166
}
167
const uint8_t n = MIN(item_size - item_ofs, count);
168
memcpy(ubuf, &ibuf[item_ofs], n);
169
ubuf += n;
170
count -= n;
171
total += n;
172
item_ofs = 0;
173
data_ofs += n;
174
}
175
176
r.file_ofs += total;
177
return total + header_total;
178
}
179
180
int32_t AP_Filesystem_Mission::lseek(int fd, int32_t offset, int seek_from)
181
{
182
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
183
errno = EBADF;
184
return -1;
185
}
186
struct rfile &r = file[fd];
187
switch (seek_from) {
188
case SEEK_SET:
189
r.file_ofs = offset;
190
break;
191
case SEEK_CUR:
192
r.file_ofs += offset;
193
break;
194
case SEEK_END:
195
errno = EINVAL;
196
return -1;
197
}
198
return r.file_ofs;
199
}
200
201
int AP_Filesystem_Mission::stat(const char *name, struct stat *stbuf)
202
{
203
enum MAV_MISSION_TYPE mtype;
204
if (!check_file_name(name, mtype)) {
205
errno = ENOENT;
206
return -1;
207
}
208
memset(stbuf, 0, sizeof(*stbuf));
209
// give fixed size to avoid needing to scan entire file
210
stbuf->st_size = 1024*1024;
211
return 0;
212
}
213
214
/*
215
check for the right file name
216
*/
217
bool AP_Filesystem_Mission::check_file_name(const char *name, enum MAV_MISSION_TYPE &mtype)
218
{
219
#if AP_MISSION_ENABLED
220
if (strcmp(name, "mission.dat") == 0) {
221
mtype = MAV_MISSION_TYPE_MISSION;
222
return true;
223
}
224
#endif
225
#if AP_FENCE_ENABLED
226
if (strcmp(name, "fence.dat") == 0) {
227
mtype = MAV_MISSION_TYPE_FENCE;
228
return true;
229
}
230
#endif
231
#if HAL_RALLY_ENABLED
232
if (strcmp(name, "rally.dat") == 0) {
233
mtype = MAV_MISSION_TYPE_RALLY;
234
return true;
235
}
236
#endif
237
return false;
238
}
239
240
/*
241
get one item
242
*/
243
bool AP_Filesystem_Mission::get_item(uint32_t idx, enum MAV_MISSION_TYPE mtype, mavlink_mission_item_int_t &item) const
244
{
245
switch (mtype) {
246
case MAV_MISSION_TYPE_MISSION: {
247
auto *mission = AP::mission();
248
if (!mission) {
249
return false;
250
}
251
return mission->get_item(idx, item);
252
}
253
#if AP_FENCE_ENABLED
254
case MAV_MISSION_TYPE_FENCE:
255
return MissionItemProtocol_Fence::get_item_as_mission_item(idx, item);
256
#endif
257
#if HAL_RALLY_ENABLED
258
case MAV_MISSION_TYPE_RALLY:
259
return MissionItemProtocol_Rally::get_item_as_mission_item(idx, item);
260
#endif
261
default:
262
break;
263
}
264
return false;
265
}
266
267
// get number of items
268
uint32_t AP_Filesystem_Mission::get_num_items(enum MAV_MISSION_TYPE mtype) const
269
{
270
switch (mtype) {
271
#if AP_MISSION_ENABLED
272
case MAV_MISSION_TYPE_MISSION: {
273
auto *mission = AP::mission();
274
if (!mission) {
275
return 0;
276
}
277
return mission->num_commands();
278
}
279
#endif
280
281
#if AP_FENCE_ENABLED
282
case MAV_MISSION_TYPE_FENCE: {
283
auto *fence = AP::fence();
284
if (fence == nullptr) {
285
return 0;
286
}
287
return fence->polyfence().num_stored_items();
288
}
289
#endif
290
291
#if HAL_RALLY_ENABLED
292
case MAV_MISSION_TYPE_RALLY: {
293
auto *rally = AP::rally();
294
if (rally == nullptr) {
295
return 0;
296
}
297
return rally->get_rally_total();
298
}
299
#endif
300
301
default:
302
break;
303
}
304
return 0;
305
}
306
307
/*
308
support mission upload
309
*/
310
int32_t AP_Filesystem_Mission::write(int fd, const void *buf, uint32_t count)
311
{
312
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
313
errno = EBADF;
314
return -1;
315
}
316
struct rfile &r = file[fd];
317
if (r.writebuf == nullptr) {
318
errno = EBADF;
319
return -1;
320
}
321
r.last_op_ms = AP_HAL::millis();
322
struct header hdr;
323
if (r.file_ofs == 0 && count >= sizeof(hdr)) {
324
// pre-expand the buffer to the full size when we get the header
325
memcpy(&hdr, buf, sizeof(hdr));
326
if (hdr.num_items < 0xFFFF) {
327
const uint32_t flen = sizeof(hdr) + hdr.num_items * MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;
328
if (flen > r.writebuf->get_length()) {
329
if (!r.writebuf->append(nullptr, flen - r.writebuf->get_length())) {
330
// not enough memory
331
errno = ENOSPC;
332
return -1;
333
}
334
}
335
}
336
}
337
if (r.file_ofs + count > r.writebuf->get_length()) {
338
if (!r.writebuf->append(nullptr, r.file_ofs + count - r.writebuf->get_length())) {
339
errno = ENOSPC;
340
return -1;
341
}
342
}
343
uint8_t *b = (uint8_t *)r.writebuf->get_writeable_string();
344
memcpy(&b[r.file_ofs], buf, count);
345
r.file_ofs += count;
346
return count;
347
}
348
349
// see if a block of memory is all zero
350
bool AP_Filesystem_Mission::all_zero(const uint8_t *b, uint8_t len) const
351
{
352
while (len--) {
353
if (*b++ != 0) {
354
return false;
355
}
356
}
357
return true;
358
}
359
360
/*
361
finish mission upload
362
*/
363
bool AP_Filesystem_Mission::finish_upload(const rfile &r)
364
{
365
const uint32_t flen = r.writebuf->get_length();
366
const uint8_t *b = (const uint8_t *)r.writebuf->get_string();
367
struct header hdr;
368
if (flen < sizeof(hdr)) {
369
return false;
370
}
371
const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;
372
const uint32_t nitems = (flen - sizeof(hdr)) / item_size;
373
374
memcpy(&hdr, b, sizeof(hdr));
375
if (hdr.magic != mission_magic) {
376
return false;
377
}
378
if (nitems != hdr.num_items) {
379
return false;
380
}
381
382
// if any item is all zeros then reject, it means client didn't
383
// fill in the whole file
384
for (uint32_t i=0; i<nitems; i++) {
385
const uint8_t *b2 = b + sizeof(hdr) + i*item_size;
386
if (all_zero(b2, item_size)) {
387
return false;
388
}
389
}
390
391
switch (r.mtype) {
392
#if AP_MISSION_ENABLED
393
case MAV_MISSION_TYPE_MISSION:
394
return finish_upload_mission(hdr, r, b);
395
#endif
396
#if HAL_RALLY_ENABLED
397
case MAV_MISSION_TYPE_RALLY:
398
return finish_upload_rally(hdr, r, b);
399
#endif
400
#if AP_FENCE_ENABLED
401
case MAV_MISSION_TYPE_FENCE:
402
return finish_upload_fence(hdr, r, b);
403
#endif
404
default:
405
// really should not get here....
406
break;
407
}
408
409
return false;
410
}
411
412
#if AP_MISSION_ENABLED
413
bool AP_Filesystem_Mission::finish_upload_mission(const struct header &hdr, const rfile &r, const uint8_t *b)
414
{
415
auto *mission = AP::mission();
416
if (mission == nullptr) {
417
return false;
418
}
419
WITH_SEMAPHORE(mission->get_semaphore());
420
if ((hdr.options & unsigned(Options::NO_CLEAR)) == 0) {
421
mission->clear();
422
}
423
for (uint32_t i=0; i<hdr.num_items; i++) {
424
mavlink_mission_item_int_t m {};
425
AP_Mission::Mission_Command cmd;
426
const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;
427
memcpy(&m, &b[sizeof(hdr)+i*item_size], item_size);
428
const MAV_MISSION_RESULT res = AP_Mission::mavlink_int_to_mission_cmd(m, cmd);
429
if (res != MAV_MISSION_ACCEPTED) {
430
return false;
431
}
432
if (cmd.id == MAV_CMD_DO_JUMP &&
433
(cmd.content.jump.target >= hdr.num_items || cmd.content.jump.target == 0)) {
434
return false;
435
}
436
uint16_t idx = i + hdr.start;
437
if (idx == mission->num_commands()) {
438
if (!mission->add_cmd(cmd)) {
439
return false;
440
}
441
} else {
442
if (!mission->replace_cmd(idx, cmd)) {
443
return false;
444
}
445
}
446
}
447
return true;
448
}
449
#endif // AP_MISSION_ENABLED
450
451
#if AP_FENCE_ENABLED
452
bool AP_Filesystem_Mission::finish_upload_fence(const struct header &hdr, const rfile &r, const uint8_t *b)
453
{
454
bool success = false;
455
456
AC_PolyFenceItem *new_items = nullptr;
457
458
auto *fence = AP::fence();
459
if (fence == nullptr) {
460
goto OUT;
461
}
462
463
if ((hdr.options & unsigned(Options::NO_CLEAR)) != 0) {
464
// Only complete fences can be uploaded for now.
465
goto OUT;
466
}
467
468
// passing nullptr and 0 items through to Polyfence loader is
469
// absolutely OK:
470
if (hdr.num_items != 0) {
471
new_items = NEW_NOTHROW AC_PolyFenceItem[hdr.num_items];
472
if (new_items == nullptr) {
473
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Out of memory for upload");
474
goto OUT;
475
}
476
}
477
478
// convert from MISSION_ITEM_INT to AC_PolyFenceItem:
479
for (uint32_t i=0; i<hdr.num_items; i++) {
480
mavlink_mission_item_int_t m {};
481
const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;
482
memcpy(&m, &b[sizeof(hdr)+i*item_size], item_size);
483
const MAV_MISSION_RESULT res = MissionItemProtocol_Fence::convert_MISSION_ITEM_INT_to_AC_PolyFenceItem(m, new_items[i]);
484
if (res != MAV_MISSION_ACCEPTED) {
485
goto OUT;
486
}
487
}
488
489
success = fence->polyfence().write_fence(new_items, hdr.num_items);
490
491
OUT:
492
493
delete[] new_items;
494
495
return success;
496
}
497
#endif // AP_FENCE_ENABLED
498
499
#if HAL_RALLY_ENABLED
500
bool AP_Filesystem_Mission::finish_upload_rally(const struct header &hdr, const rfile &r, const uint8_t *b)
501
{
502
bool success = false;
503
504
auto *rally = AP::rally();
505
if (rally == nullptr) {
506
goto OUT;
507
}
508
509
if ((hdr.options & unsigned(Options::NO_CLEAR)) != 0) {
510
//only complete sets of rally points can be added ATM
511
goto OUT;
512
}
513
514
rally->truncate(0);
515
516
for (uint32_t i=0; i<hdr.num_items; i++) {
517
mavlink_mission_item_int_t m {};
518
RallyLocation cmd;
519
const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;
520
memcpy(&m, &b[sizeof(hdr)+i*item_size], item_size);
521
const MAV_MISSION_RESULT res = MissionItemProtocol_Rally::convert_MISSION_ITEM_INT_to_RallyLocation(m, cmd);
522
if (res != MAV_MISSION_ACCEPTED) {
523
goto OUT;
524
}
525
526
if (!rally->append(cmd)) {
527
goto OUT;
528
}
529
}
530
success = true;
531
532
OUT:
533
return success;
534
}
535
#endif // HAL_RALLY_ENABLED
536
537
#endif // AP_FILESYSTEM_MISSION_ENABLED
538
539