• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 21655938172

04 Feb 2026 02:23AM UTC coverage: 49.021% (+0.06%) from 48.959%
21655938172

Pull #2762

github

web-flow
Merge 98ac24bde into b84eae3a5
Pull Request #2762: core: fix MAVLink message sequence

34 of 35 new or added lines in 2 files covered. (97.14%)

2 existing lines in 2 files now uncovered.

18354 of 37441 relevant lines covered (49.02%)

671.39 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

73.21
/src/mavsdk/core/mavlink_ftp_client.cpp
1
#include "mavlink_ftp_client.h"
2
#include "system_impl.h"
3
#include "overloaded.h"
4
#include "unused.h"
5
#include <algorithm>
6
#include <fstream>
7
#include <filesystem>
8
#include <algorithm>
9
#include <numeric>
10

11
#include "crc32.h"
12

13
namespace mavsdk {
14

15
namespace fs = std::filesystem;
16

17
MavlinkFtpClient::MavlinkFtpClient(SystemImpl& system_impl) : _system_impl(system_impl)
152✔
18
{
19
    if (const char* env_p = std::getenv("MAVSDK_FTP_DEBUGGING")) {
152✔
20
        if (std::string(env_p) == "1") {
×
21
            LogDebug() << "Ftp debugging is on.";
×
22
            _debugging = true;
×
23
        }
24
    }
25

26
    _system_impl.register_mavlink_message_handler(
152✔
27
        MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL,
28
        [this](const mavlink_message_t& message) { process_mavlink_ftp_message(message); },
1,239✔
29
        this);
30
}
152✔
31

32
MavlinkFtpClient::~MavlinkFtpClient()
152✔
33
{
34
    stop_timer();
152✔
35
    _system_impl.unregister_all_mavlink_message_handlers(this);
152✔
36
}
152✔
37

38
void MavlinkFtpClient::do_work()
20,195✔
39
{
40
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
20,195✔
41

42
    auto work = work_queue_guard.get_front();
19,814✔
43
    if (!work) {
19,870✔
44
        return;
19,181✔
45
    }
46

47
    if (work->started) {
898✔
48
        return;
857✔
49
    }
50
    work->started = true;
41✔
51

52
    // We're mainly starting the process here. After that, it continues
53
    // based on returned acks or timeouts.
54

55
    std::visit(
41✔
56
        overloaded{
82✔
57
            [&](DownloadItem& item) {
8✔
58
                if (!download_start(*work, item)) {
8✔
59
                    work_queue_guard.pop_front();
×
60
                }
61
            },
8✔
62
            [&](DownloadBurstItem& item) {
10✔
63
                if (!download_burst_start(*work, item)) {
10✔
64
                    work_queue_guard.pop_front();
×
65
                }
66
            },
10✔
67
            [&](UploadItem& item) {
7✔
68
                if (!upload_start(*work, item)) {
7✔
69
                    work_queue_guard.pop_front();
×
70
                }
71
            },
7✔
72
            [&](RemoveItem& item) {
4✔
73
                if (!remove_start(*work, item)) {
4✔
74
                    work_queue_guard.pop_front();
×
75
                }
76
            },
4✔
77
            [&](RenameItem& item) {
2✔
78
                if (!rename_start(*work, item)) {
2✔
79
                    work_queue_guard.pop_front();
×
80
                }
81
            },
2✔
82
            [&](CreateDirItem& item) {
3✔
83
                if (!create_dir_start(*work, item)) {
3✔
84
                    work_queue_guard.pop_front();
×
85
                }
86
            },
3✔
87
            [&](RemoveDirItem& item) {
2✔
88
                if (!remove_dir_start(*work, item)) {
2✔
89
                    work_queue_guard.pop_front();
×
90
                }
91
            },
2✔
92
            [&](CompareFilesItem& item) {
3✔
93
                if (!compare_files_start(*work, item)) {
3✔
94
                    work_queue_guard.pop_front();
×
95
                }
96
            },
3✔
97
            [&](ListDirItem& item) {
2✔
98
                if (!list_dir_start(*work, item)) {
2✔
99
                    work_queue_guard.pop_front();
×
100
                }
101
            }},
2✔
102
        work->item);
41✔
103
}
40,052✔
104

105
void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg)
1,239✔
106
{
107
    mavlink_file_transfer_protocol_t ftp_req;
108
    mavlink_msg_file_transfer_protocol_decode(&msg, &ftp_req);
1,239✔
109

110
    if (ftp_req.target_system != 0 && ftp_req.target_system != _system_impl.get_own_system_id()) {
1,239✔
111
        if (_debugging) {
×
112
            LogDebug() << "Received FTP message with wrong target system ID";
×
113
        }
114
        return;
506✔
115
    }
116

117
    if (ftp_req.target_component != 0 &&
2,460✔
118
        ftp_req.target_component != _system_impl.get_own_component_id()) {
1,221✔
119
        if (_debugging) {
9✔
120
            LogDebug() << "Received FTP message with wrong target component ID";
×
121
        }
122
        return;
9✔
123
    }
124

125
    PayloadHeader* payload = reinterpret_cast<PayloadHeader*>(&ftp_req.payload[0]);
1,230✔
126

127
    if (payload->size > max_data_length) {
1,230✔
128
        LogWarn() << "Received FTP payload with invalid size";
×
129
        return;
×
130
    } else {
131
        if (_debugging) {
1,230✔
132
            LogDebug() << "FTP: opcode: " << (int)payload->opcode
×
133
                       << ", req_opcode: " << (int)payload->req_opcode
×
134
                       << ", size: " << (int)payload->size << ", offset: " << (int)payload->offset
×
135
                       << ", seq: " << payload->seq_number << " from: " << (int)msg.sysid << "/"
×
136
                       << (int)msg.compid;
×
137
        }
138
    }
139

140
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
1,230✔
141

142
    auto work = work_queue_guard.get_front();
1,230✔
143
    if (!work) {
1,230✔
144
        return;
488✔
145
    }
146

147
    if (work->last_opcode != payload->req_opcode) {
742✔
148
        // Ignore
149
        LogWarn() << "Ignore: last: " << (int)work->last_opcode
9✔
150
                  << ", req: " << (int)payload->req_opcode;
9✔
151
        return;
9✔
152
    }
153
    if (work->last_received_seq_number != 0 &&
1,425✔
154
        work->last_received_seq_number == payload->seq_number) {
692✔
155
        // We have already seen this ack/nak.
156
        LogWarn() << "Already seen";
×
157
        return;
×
158
    }
159

160
    std::visit(
733✔
161
        overloaded{
1,466✔
162
            [&](DownloadItem& item) {
306✔
163
                if (payload->opcode == RSP_ACK) {
306✔
164
                    if (payload->req_opcode == CMD_OPEN_FILE_RO ||
304✔
165
                        payload->req_opcode == CMD_READ_FILE) {
298✔
166
                        // Whenever we do get an ack,
167
                        // reset the retry counter.
168
                        work->retries = RETRIES;
299✔
169

170
                        if (!download_continue(*work, item, payload)) {
299✔
171
                            stop_timer();
×
172
                            work_queue_guard.pop_front();
×
173
                        }
174
                    } else if (payload->req_opcode == CMD_TERMINATE_SESSION) {
5✔
175
                        stop_timer();
5✔
176
                        item.ofstream.close();
5✔
177
                        item.callback(ClientResult::Success, {});
5✔
178
                        work_queue_guard.pop_front();
5✔
179

180
                    } else {
181
                        LogWarn() << "Unexpected ack";
×
182
                    }
183

184
                } else if (payload->opcode == RSP_NAK) {
2✔
185
                    stop_timer();
2✔
186
                    item.callback(result_from_nak(payload), {});
2✔
187
                    terminate_session(*work);
2✔
188
                    work_queue_guard.pop_front();
2✔
189
                }
190
            },
306✔
191
            [&](DownloadBurstItem& item) {
295✔
192
                if (payload->opcode == RSP_ACK) {
295✔
193
                    if (payload->req_opcode == CMD_OPEN_FILE_RO ||
293✔
194
                        payload->req_opcode == CMD_BURST_READ_FILE ||
285✔
195
                        payload->req_opcode == CMD_READ_FILE) {
14✔
196
                        // Whenever we do get an ack,
197
                        // reset the retry counter.
198
                        work->retries = RETRIES;
287✔
199

200
                        if (!download_burst_continue(*work, item, payload)) {
287✔
201
                            stop_timer();
×
202
                            work_queue_guard.pop_front();
×
203
                        }
204
                    } else if (payload->req_opcode == CMD_TERMINATE_SESSION) {
6✔
205
                        stop_timer();
6✔
206
                        item.ofstream.close();
6✔
207
                        item.callback(ClientResult::Success, {});
6✔
208
                        work_queue_guard.pop_front();
6✔
209

210
                    } else {
211
                        LogWarn() << "Unexpected ack";
×
212
                    }
213

214
                } else if (payload->opcode == RSP_NAK) {
2✔
215
                    const ServerResult sr = static_cast<ServerResult>(payload->data[0]);
2✔
216
                    // In case there's no session available, there's another transfer in progress
217
                    // for the given component. Back off and try again later.
218
                    if (sr == ERR_NO_SESSIONS_AVAILABLE) {
2✔
219
                        payload->seq_number = 0; // Ignore this response
×
220
                        start_timer(3.0);
×
221
                        LogDebug() << "No session available, retrying...";
×
222
                    } else {
223
                        LogWarn() << "FTP: NAK received";
2✔
224
                        stop_timer();
2✔
225
                        item.callback(result_from_nak(payload), {});
2✔
226
                        terminate_session(*work);
2✔
227
                        work_queue_guard.pop_front();
2✔
228
                    }
229
                }
230
            },
295✔
231
            [&](UploadItem& item) {
107✔
232
                if (payload->opcode == RSP_ACK) {
107✔
233
                    if (payload->req_opcode == CMD_CREATE_FILE ||
105✔
234
                        payload->req_opcode == CMD_OPEN_FILE_WO ||
100✔
235
                        payload->req_opcode == CMD_WRITE_FILE) {
100✔
236
                        // Whenever we do get an ack,
237
                        // reset the retry counter.
238
                        work->retries = RETRIES;
101✔
239

240
                        if (!upload_continue(*work, item)) {
101✔
241
                            stop_timer();
×
242
                            work_queue_guard.pop_front();
×
243
                        }
244
                    } else if (payload->req_opcode == CMD_TERMINATE_SESSION) {
4✔
245
                        stop_timer();
4✔
246
                        item.ifstream.close();
4✔
247
                        item.callback(ClientResult::Success, {});
4✔
248
                        work_queue_guard.pop_front();
4✔
249

250
                    } else {
251
                        LogWarn() << "Unexpected ack";
×
252
                    }
253

254
                } else if (payload->opcode == RSP_NAK) {
2✔
255
                    stop_timer();
2✔
256
                    item.callback(result_from_nak(payload), {});
2✔
257
                    terminate_session(*work);
2✔
258
                    work_queue_guard.pop_front();
2✔
259
                }
260
            },
107✔
261
            [&](RemoveItem& item) {
4✔
262
                if (payload->opcode == RSP_ACK) {
4✔
263
                    if (payload->req_opcode == CMD_REMOVE_FILE) {
1✔
264
                        stop_timer();
1✔
265
                        item.callback(ClientResult::Success);
1✔
266
                        work_queue_guard.pop_front();
1✔
267

268
                    } else {
269
                        LogWarn() << "Unexpected ack";
×
270
                    }
271

272
                } else if (payload->opcode == RSP_NAK) {
3✔
273
                    stop_timer();
3✔
274
                    item.callback(result_from_nak(payload));
3✔
275
                    terminate_session(*work);
3✔
276
                    work_queue_guard.pop_front();
3✔
277
                }
278
            },
4✔
279
            [&](RenameItem& item) {
2✔
280
                if (payload->opcode == RSP_ACK) {
2✔
281
                    if (payload->req_opcode == CMD_RENAME) {
1✔
282
                        stop_timer();
1✔
283
                        item.callback(ClientResult::Success);
1✔
284
                        work_queue_guard.pop_front();
1✔
285

286
                    } else {
287
                        LogWarn() << "Unexpected ack";
×
288
                    }
289

290
                } else if (payload->opcode == RSP_NAK) {
1✔
291
                    stop_timer();
1✔
292
                    item.callback(result_from_nak(payload));
1✔
293
                    terminate_session(*work);
1✔
294
                    work_queue_guard.pop_front();
1✔
295
                }
296
            },
2✔
297
            [&](CreateDirItem& item) {
3✔
298
                if (payload->opcode == RSP_ACK) {
3✔
299
                    if (payload->req_opcode == CMD_CREATE_DIRECTORY) {
1✔
300
                        stop_timer();
1✔
301
                        item.callback(ClientResult::Success);
1✔
302
                        work_queue_guard.pop_front();
1✔
303

304
                    } else {
305
                        LogWarn() << "Unexpected ack";
×
306
                    }
307

308
                } else if (payload->opcode == RSP_NAK) {
2✔
309
                    stop_timer();
2✔
310
                    item.callback(result_from_nak(payload));
2✔
311
                    terminate_session(*work);
2✔
312
                    work_queue_guard.pop_front();
2✔
313
                }
314
            },
3✔
315
            [&](RemoveDirItem& item) {
2✔
316
                if (payload->opcode == RSP_ACK) {
2✔
317
                    if (payload->req_opcode == CMD_REMOVE_DIRECTORY) {
1✔
318
                        stop_timer();
1✔
319
                        item.callback(ClientResult::Success);
1✔
320
                        work_queue_guard.pop_front();
1✔
321

322
                    } else {
323
                        LogWarn() << "Unexpected ack";
×
324
                    }
325

326
                } else if (payload->opcode == RSP_NAK) {
1✔
327
                    stop_timer();
1✔
328
                    item.callback(result_from_nak(payload));
1✔
329
                    terminate_session(*work);
1✔
330
                    work_queue_guard.pop_front();
1✔
331
                }
332
            },
2✔
333
            [&](CompareFilesItem& item) {
3✔
334
                if (payload->opcode == RSP_ACK) {
3✔
335
                    if (payload->req_opcode == CMD_CALC_FILE_CRC32) {
2✔
336
                        stop_timer();
2✔
337
                        uint32_t remote_crc = *reinterpret_cast<uint32_t*>(payload->data);
2✔
338
                        item.callback(ClientResult::Success, remote_crc == item.local_crc);
2✔
339
                        work_queue_guard.pop_front();
2✔
340

341
                    } else {
342
                        LogWarn() << "Unexpected ack";
×
343
                    }
344

345
                } else if (payload->opcode == RSP_NAK) {
1✔
346
                    stop_timer();
1✔
347
                    item.callback(result_from_nak(payload), false);
1✔
348
                    terminate_session(*work);
1✔
349
                    work_queue_guard.pop_front();
1✔
350
                }
351
            },
3✔
352
            [&](ListDirItem& item) {
11✔
353
                if (payload->opcode == RSP_ACK) {
11✔
354
                    if (payload->req_opcode == CMD_LIST_DIRECTORY) {
9✔
355
                        // Whenever we do get an ack, reset the retry counter.
356
                        work->retries = RETRIES;
9✔
357

358
                        if (!list_dir_continue(*work, item, payload)) {
9✔
359
                            stop_timer();
×
360
                            work_queue_guard.pop_front();
×
361
                        }
362
                    } else {
363
                        LogWarn() << "Unexpected ack";
×
364
                    }
365

366
                } else if (payload->opcode == RSP_NAK) {
2✔
367
                    stop_timer();
2✔
368
                    if (payload->data[0] == ERR_EOF) {
2✔
369
                        std::sort(item.dirs.begin(), item.dirs.end());
1✔
370
                        std::sort(item.files.begin(), item.files.end());
1✔
371
                        item.callback(ClientResult::Success, item.dirs, item.files);
1✔
372
                    } else {
373
                        item.callback(result_from_nak(payload), {}, {});
1✔
374
                    }
375
                    terminate_session(*work);
2✔
376
                    work_queue_guard.pop_front();
2✔
377
                }
378
            }},
11✔
379
        work->item);
733✔
380

381
    work->last_received_seq_number = payload->seq_number;
733✔
382
}
1,727✔
383

384
bool MavlinkFtpClient::download_start(Work& work, DownloadItem& item)
8✔
385
{
386
    fs::path local_path = fs::path(item.local_folder) / fs::path(item.remote_path).filename();
16✔
387
    fs::create_directories(fs::path(item.local_folder));
8✔
388

389
    if (_debugging) {
8✔
390
        LogDebug() << "Trying to open write to local path: " << local_path.string();
×
391
    }
392

393
    item.ofstream.open(local_path, std::fstream::trunc | std::fstream::binary);
8✔
394
    if (!item.ofstream) {
8✔
395
        LogErr() << "Could not open it!";
×
396
        item.callback(ClientResult::FileIoError, {});
×
397
        return false;
×
398
    }
399

400
    work.last_opcode = CMD_OPEN_FILE_RO;
8✔
401
    work.payload = {};
8✔
402
    work.payload.seq_number = _last_sent_seq_number++;
8✔
403
    work.payload.session = _session;
8✔
404
    work.payload.opcode = work.last_opcode;
8✔
405
    work.payload.offset = 0;
8✔
406
    strncpy(
8✔
407
        reinterpret_cast<char*>(work.payload.data), item.remote_path.c_str(), max_data_length - 1);
8✔
408
    work.payload.size = item.remote_path.length() + 1;
8✔
409

410
    start_timer();
8✔
411
    send_mavlink_ftp_message(work.payload, work.target_compid);
8✔
412

413
    return true;
8✔
414
}
8✔
415

416
bool MavlinkFtpClient::download_continue(Work& work, DownloadItem& item, PayloadHeader* payload)
299✔
417
{
418
    if (payload->req_opcode == CMD_OPEN_FILE_RO) {
299✔
419
        item.file_size = *(reinterpret_cast<uint32_t*>(payload->data));
6✔
420

421
        if (_debugging) {
6✔
422
            LogWarn() << "Download continue, got file size: " << item.file_size;
×
423
        }
424

425
    } else if (payload->req_opcode == CMD_READ_FILE) {
293✔
426
        if (_debugging) {
293✔
427
            LogWarn() << "Download continue, write: " << std::to_string(payload->size);
×
428
        }
429

430
        if (item.bytes_transferred < item.file_size) {
293✔
431
            item.ofstream.write(reinterpret_cast<const char*>(payload->data), payload->size);
293✔
432
            if (!item.ofstream) {
293✔
433
                item.callback(ClientResult::FileIoError, {});
×
434
                return false;
×
435
            }
436
            item.bytes_transferred += payload->size;
293✔
437

438
            if (_debugging) {
293✔
439
                LogDebug() << "Written " << item.bytes_transferred << " of " << item.file_size
×
440
                           << " bytes";
×
441
            }
442
        }
443
        item.callback(
293✔
444
            ClientResult::Next,
445
            ProgressData{
446
                static_cast<uint32_t>(item.bytes_transferred),
293✔
447
                static_cast<uint32_t>(item.file_size)});
293✔
448
    }
449

450
    if (item.bytes_transferred < item.file_size) {
299✔
451
        work.last_opcode = CMD_READ_FILE;
294✔
452
        work.payload = {};
294✔
453
        work.payload.seq_number = _last_sent_seq_number++;
294✔
454
        work.payload.session = _session;
294✔
455
        work.payload.opcode = work.last_opcode;
294✔
456
        work.payload.offset = item.bytes_transferred;
294✔
457

458
        work.payload.size =
294✔
459
            std::min(static_cast<size_t>(max_data_length), item.file_size - item.bytes_transferred);
294✔
460

461
        if (_debugging) {
294✔
462
            LogWarn() << "Request size: " << std::to_string(work.payload.size) << " of left "
×
463
                      << int(item.file_size - item.bytes_transferred);
×
464
        }
465

466
        start_timer();
294✔
467
        send_mavlink_ftp_message(work.payload, work.target_compid);
294✔
468

469
        return true;
294✔
470
    } else {
471
        if (_debugging) {
5✔
472
            LogDebug() << "All bytes written, terminating session";
×
473
        }
474

475
        start_timer();
5✔
476
        terminate_session(work);
5✔
477
        return true;
5✔
478
    }
479

480
    return true;
481
}
482

483
bool MavlinkFtpClient::download_burst_start(Work& work, DownloadBurstItem& item)
10✔
484
{
485
    fs::path local_path = fs::path(item.local_folder) / fs::path(item.remote_path).filename();
20✔
486

487
    if (_debugging) {
10✔
488
        LogDebug() << "Trying to open write to local path: " << local_path.string();
×
489
    }
490

491
    item.ofstream.open(local_path, std::fstream::trunc | std::fstream::binary);
10✔
492
    if (!item.ofstream) {
10✔
493
        LogErr() << "Could not open it!";
×
494
        item.callback(ClientResult::FileIoError, {});
×
495
        return false;
×
496
    }
497

498
    work.last_opcode = CMD_OPEN_FILE_RO;
10✔
499
    work.payload = {};
10✔
500
    work.payload.seq_number = _last_sent_seq_number++;
10✔
501
    work.payload.session = _session;
10✔
502
    work.payload.opcode = work.last_opcode;
10✔
503
    work.payload.offset = 0;
10✔
504
    strncpy(
10✔
505
        reinterpret_cast<char*>(work.payload.data), item.remote_path.c_str(), max_data_length - 1);
10✔
506
    work.payload.size = item.remote_path.length() + 1;
10✔
507

508
    start_timer();
10✔
509
    send_mavlink_ftp_message(work.payload, work.target_compid);
10✔
510

511
    return true;
10✔
512
}
10✔
513

514
bool MavlinkFtpClient::download_burst_continue(
287✔
515
    Work& work, DownloadBurstItem& item, PayloadHeader* payload)
516
{
517
    if (payload->req_opcode == CMD_OPEN_FILE_RO) {
287✔
518
        std::memcpy(&(item.file_size), payload->data, sizeof(uint32_t));
8✔
519

520
        if (_debugging) {
8✔
521
            LogDebug() << "Burst Download continue, got file size: " << item.file_size;
×
522
        }
523

524
        request_burst(work, item);
8✔
525

526
    } else if (payload->req_opcode == CMD_BURST_READ_FILE) {
279✔
527
        if (_debugging) {
271✔
528
            LogDebug() << "Burst download continue, at: " << std::to_string(payload->offset)
×
529
                       << " write: " << std::to_string(payload->size);
×
530
        }
531

532
        if (payload->offset != item.current_offset) {
271✔
533
            if (payload->offset < item.current_offset) {
8✔
534
                // Not sure why this would happen but we don't know how to deal with it and ignore
535
                // it.
536
                LogWarn() << "Got payload offset: " << payload->offset
×
537
                          << ", next offset: " << item.current_offset;
×
538
                return false;
×
539
            }
540

541
            // we missed a part
542
            item.missing_data.emplace_back(DownloadBurstItem::MissingData{
16✔
543
                item.current_offset, payload->offset - item.current_offset});
8✔
544
            // write some 0 instead
545
            std::vector<char> empty(payload->offset - item.current_offset);
8✔
546
            item.ofstream.write(empty.data(), empty.size());
8✔
547
            if (!item.ofstream) {
8✔
548
                LogWarn() << "Write failed";
×
549
                item.callback(ClientResult::FileIoError, {});
×
550
                download_burst_end(work);
×
551
                return false;
×
552
            }
553
        }
8✔
554

555
        // Write actual data to file.
556
        item.ofstream.write(reinterpret_cast<const char*>(payload->data), payload->size);
271✔
557
        if (!item.ofstream) {
271✔
558
            LogWarn() << "Write failed";
×
559
            item.callback(ClientResult::FileIoError, {});
×
560
            download_burst_end(work);
×
561
            return false;
×
562
        }
563

564
        // Keep track of what was written.
565
        item.current_offset = payload->offset + payload->size;
271✔
566

567
        if (_debugging) {
271✔
568
            LogDebug() << "Received " << payload->offset << " to "
×
569
                       << payload->size + payload->offset;
×
570
        }
571

572
        if (payload->size + payload->offset >= item.file_size) {
271✔
573
            if (_debugging) {
7✔
574
                LogDebug() << "Burst complete";
×
575
            }
576

577
            if (item.missing_data.empty()) {
7✔
578
                // No missing data, we're done.
579

580
                // Final step
581
                download_burst_end(work);
6✔
582
            } else {
583
                // The burst is supposedly complete but we still need data because
584
                // we missed some, so request next without burst.
585
                request_next_rest(work, item);
1✔
586
            }
587
        } else {
588
            item.callback(
528✔
589
                ClientResult::Next,
590
                ProgressData{
591
                    static_cast<uint32_t>(burst_bytes_transferred(item)),
264✔
592
                    static_cast<uint32_t>(item.file_size)});
264✔
593

594
            if (payload->burst_complete) {
264✔
595
                // This burst is complete but the file isn't. we need to start a
596
                // new one
597
                request_burst(work, item);
×
598
            } else {
599
                // There might be more coming, just wait for now.
600
                start_timer();
264✔
601
            }
602
        }
603
    } else if (payload->req_opcode == CMD_READ_FILE) {
8✔
604
        if (_debugging) {
8✔
605
            LogWarn() << "Burst download continue missing pieces, write at " << payload->offset
×
606
                      << " for " << std::to_string(payload->size);
×
607
        }
608

609
        item.ofstream.seekp(payload->offset);
8✔
610
        if (item.ofstream.fail()) {
8✔
611
            LogWarn() << "Seek failed";
×
612
            item.callback(ClientResult::FileIoError, {});
×
613
            download_burst_end(work);
×
614
            return false;
×
615
        }
616

617
        item.ofstream.write(reinterpret_cast<const char*>(payload->data), payload->size);
8✔
618
        if (!item.ofstream) {
8✔
619
            item.callback(ClientResult::FileIoError, {});
×
620
            download_burst_end(work);
×
621
            return false;
×
622
        }
623

624
        auto& missing = item.missing_data.front();
8✔
625
        if (missing.offset != payload->offset) {
8✔
626
            LogErr() << "Offset mismatch";
×
627
            item.callback(ClientResult::ProtocolError, {});
×
628
            download_burst_end(work);
×
629
            return false;
×
630
        }
631

632
        if (missing.size <= payload->size) {
8✔
633
            // we got all needed data for this chunk
634
            item.missing_data.pop_front();
8✔
635
        } else {
636
            missing.offset += payload->size;
×
637
            missing.size -= payload->size;
×
638
        }
639

640
        // Check if this was the last one
641
        if (item.file_size == payload->offset + payload->size) {
8✔
UNCOV
642
            item.current_offset = item.file_size;
×
643
        }
644

645
        const size_t bytes_transferred = burst_bytes_transferred(item);
8✔
646

647
        if (_debugging) {
8✔
648
            LogDebug() << "Written " << bytes_transferred << " of " << item.file_size << " bytes";
×
649
        }
650

651
        if (item.missing_data.empty() && bytes_transferred == item.file_size) {
8✔
652
            // Final step
653
            download_burst_end(work);
1✔
654
        } else {
655
            item.callback(
7✔
656
                ClientResult::Next,
657
                ProgressData{
658
                    static_cast<uint32_t>(bytes_transferred),
659
                    static_cast<uint32_t>(item.file_size)});
7✔
660

661
            request_next_rest(work, item);
7✔
662
        }
663

664
    } else {
665
        LogErr() << "Unexpected req_opcode";
×
666
        download_burst_end(work);
×
667
        return false;
×
668
    }
669

670
    return true;
287✔
671
}
672

673
void MavlinkFtpClient::download_burst_end(Work& work)
8✔
674
{
675
    work.last_opcode = CMD_TERMINATE_SESSION;
8✔
676

677
    work.payload = {};
8✔
678
    work.payload.seq_number = _last_sent_seq_number++;
8✔
679
    work.payload.session = _session;
8✔
680

681
    work.payload.opcode = work.last_opcode;
8✔
682
    work.payload.offset = 0;
8✔
683
    work.payload.size = 0;
8✔
684

685
    start_timer();
8✔
686
    send_mavlink_ftp_message(work.payload, work.target_compid);
8✔
687
}
8✔
688

689
void MavlinkFtpClient::request_burst(Work& work, DownloadBurstItem& item)
8✔
690
{
691
    UNUSED(item);
8✔
692

693
    work.last_opcode = CMD_BURST_READ_FILE;
8✔
694
    work.payload = {};
8✔
695
    work.payload.seq_number = _last_sent_seq_number++;
8✔
696
    work.payload.session = _session;
8✔
697
    work.payload.opcode = work.last_opcode;
8✔
698
    work.payload.offset = item.current_offset;
8✔
699

700
    // Fill up the whole packet.
701
    work.payload.size = max_data_length;
8✔
702

703
    start_timer();
8✔
704
    send_mavlink_ftp_message(work.payload, work.target_compid);
8✔
705
}
8✔
706

707
void MavlinkFtpClient::request_next_rest(Work& work, DownloadBurstItem& item)
21✔
708
{
709
    const auto& missing = item.missing_data.front();
21✔
710
    size_t size = std::min(missing.size, size_t(max_data_length));
21✔
711

712
    if (_debugging) {
21✔
713
        LogDebug() << "Re-requesting from " << missing.offset << " with size " << size;
×
714
    }
715

716
    work.last_opcode = CMD_READ_FILE;
21✔
717
    work.payload = {};
21✔
718
    work.payload.seq_number = _last_sent_seq_number++;
21✔
719
    work.payload.session = _session;
21✔
720
    work.payload.opcode = work.last_opcode;
21✔
721
    work.payload.offset = missing.offset;
21✔
722

723
    work.payload.size = size;
21✔
724

725
    start_timer();
21✔
726
    send_mavlink_ftp_message(work.payload, work.target_compid);
21✔
727
}
21✔
728

729
size_t MavlinkFtpClient::burst_bytes_transferred(DownloadBurstItem& item)
272✔
730
{
731
    return item.current_offset - std::accumulate(
272✔
732
                                     item.missing_data.begin(),
272✔
733
                                     item.missing_data.end(),
272✔
734
                                     size_t(0),
735
                                     [](size_t acc, const DownloadBurstItem::MissingData& missing) {
156✔
736
                                         return acc + missing.size;
156✔
737
                                     });
272✔
738
}
739

740
bool MavlinkFtpClient::upload_start(Work& work, UploadItem& item)
7✔
741
{
742
    std::error_code ec;
7✔
743
    if (!fs::exists(item.local_file_path, ec)) {
7✔
744
        item.callback(ClientResult::FileDoesNotExist, {});
×
745
        return false;
×
746
    }
747

748
    item.ifstream.open(item.local_file_path, std::fstream::binary);
7✔
749
    if (!item.ifstream) {
7✔
750
        item.callback(ClientResult::FileIoError, {});
×
751
        return false;
×
752
    }
753

754
    item.file_size = fs::file_size(item.local_file_path, ec);
7✔
755
    if (ec) {
7✔
756
        LogWarn() << "Could not get file size of '" << item.local_file_path
×
757
                  << "': " << ec.message();
×
758
        return false;
×
759
    }
760

761
    fs::path remote_file_path =
762
        fs::path(item.remote_folder) / fs::path(item.local_file_path).filename();
14✔
763

764
    if (remote_file_path.string().size() >= max_data_length) {
7✔
765
        item.callback(ClientResult::InvalidParameter, {});
×
766
        return false;
×
767
    }
768

769
    work.last_opcode = CMD_CREATE_FILE;
7✔
770
    work.payload = {};
7✔
771
    work.payload.seq_number = _last_sent_seq_number++;
7✔
772
    work.payload.session = _session;
7✔
773
    work.payload.opcode = work.last_opcode;
7✔
774
    work.payload.offset = 0;
7✔
775
    strncpy(
7✔
776
        reinterpret_cast<char*>(work.payload.data),
7✔
777
        remote_file_path.string().c_str(),
14✔
778
        max_data_length - 1);
779
    work.payload.size = remote_file_path.string().size() + 1;
7✔
780

781
    start_timer();
7✔
782
    send_mavlink_ftp_message(work.payload, work.target_compid);
7✔
783

784
    return true;
7✔
785
}
7✔
786

787
bool MavlinkFtpClient::upload_continue(Work& work, UploadItem& item)
101✔
788
{
789
    if (item.bytes_transferred < item.file_size) {
101✔
790
        work.last_opcode = CMD_WRITE_FILE;
97✔
791

792
        work.payload = {};
97✔
793
        work.payload.seq_number = _last_sent_seq_number++;
97✔
794
        work.payload.session = _session;
97✔
795

796
        work.payload.opcode = work.last_opcode;
97✔
797
        work.payload.offset = item.bytes_transferred;
97✔
798

799
        std::size_t bytes_to_read =
800
            std::min(item.file_size - item.bytes_transferred, std::size_t(max_data_length));
97✔
801

802
        item.ifstream.read(reinterpret_cast<char*>(work.payload.data), bytes_to_read);
97✔
803

804
        // Get the number of bytes actually read.
805
        int bytes_read = item.ifstream.gcount();
97✔
806

807
        if (!item.ifstream) {
97✔
808
            item.callback(ClientResult::FileIoError, {});
×
809
            return false;
×
810
        }
811

812
        work.payload.size = bytes_read;
97✔
813
        item.bytes_transferred += bytes_read;
97✔
814

815
        start_timer();
97✔
816
        send_mavlink_ftp_message(work.payload, work.target_compid);
97✔
817

818
    } else {
819
        // Final step
820
        work.last_opcode = CMD_TERMINATE_SESSION;
4✔
821

822
        work.payload = {};
4✔
823
        work.payload.seq_number = _last_sent_seq_number++;
4✔
824
        work.payload.session = _session;
4✔
825

826
        work.payload.opcode = work.last_opcode;
4✔
827
        work.payload.offset = 0;
4✔
828
        work.payload.size = 0;
4✔
829

830
        start_timer();
4✔
831
        send_mavlink_ftp_message(work.payload, work.target_compid);
4✔
832
    }
833

834
    item.callback(
101✔
835
        ClientResult::Next,
836
        ProgressData{
837
            static_cast<uint32_t>(item.bytes_transferred), static_cast<uint32_t>(item.file_size)});
101✔
838

839
    return true;
101✔
840
}
841

842
bool MavlinkFtpClient::remove_start(Work& work, RemoveItem& item)
4✔
843
{
844
    if (item.path.length() >= max_data_length) {
4✔
845
        item.callback(ClientResult::InvalidParameter);
×
846
        return false;
×
847
    }
848

849
    work.last_opcode = CMD_REMOVE_FILE;
4✔
850
    work.payload = {};
4✔
851
    work.payload.seq_number = _last_sent_seq_number++;
4✔
852
    work.payload.session = _session;
4✔
853
    work.payload.opcode = work.last_opcode;
4✔
854
    work.payload.offset = 0;
4✔
855
    strncpy(reinterpret_cast<char*>(work.payload.data), item.path.c_str(), max_data_length - 1);
4✔
856
    work.payload.size = item.path.length() + 1;
4✔
857

858
    start_timer();
4✔
859
    send_mavlink_ftp_message(work.payload, work.target_compid);
4✔
860

861
    return true;
4✔
862
}
863

864
bool MavlinkFtpClient::rename_start(Work& work, RenameItem& item)
2✔
865
{
866
    if (item.from_path.length() + item.to_path.length() + 1 >= max_data_length) {
2✔
867
        item.callback(ClientResult::InvalidParameter);
×
868
        return false;
×
869
    }
870

871
    work.last_opcode = CMD_RENAME;
2✔
872
    work.payload = {};
2✔
873
    work.payload.seq_number = _last_sent_seq_number++;
2✔
874
    work.payload.session = _session;
2✔
875
    work.payload.opcode = work.last_opcode;
2✔
876
    work.payload.offset = 0;
2✔
877
    strncpy(
2✔
878
        reinterpret_cast<char*>(work.payload.data), item.from_path.c_str(), max_data_length - 1);
2✔
879
    work.payload.size = item.from_path.length() + 1;
2✔
880
    strncpy(
4✔
881
        reinterpret_cast<char*>(&work.payload.data[work.payload.size]),
2✔
882
        item.to_path.c_str(),
883
        max_data_length - work.payload.size);
2✔
884
    work.payload.size += item.to_path.length() + 1;
2✔
885
    start_timer();
2✔
886

887
    send_mavlink_ftp_message(work.payload, work.target_compid);
2✔
888

889
    return true;
2✔
890
}
891

892
bool MavlinkFtpClient::create_dir_start(Work& work, CreateDirItem& item)
3✔
893
{
894
    if (item.path.length() + 1 >= max_data_length) {
3✔
895
        item.callback(ClientResult::InvalidParameter);
×
896
        return false;
×
897
    }
898

899
    work.last_opcode = CMD_CREATE_DIRECTORY;
3✔
900
    work.payload = {};
3✔
901
    work.payload.seq_number = _last_sent_seq_number++;
3✔
902
    work.payload.session = _session;
3✔
903
    work.payload.opcode = work.last_opcode;
3✔
904
    work.payload.offset = 0;
3✔
905
    strncpy(reinterpret_cast<char*>(work.payload.data), item.path.c_str(), max_data_length - 1);
3✔
906
    work.payload.size = item.path.length() + 1;
3✔
907
    start_timer();
3✔
908

909
    send_mavlink_ftp_message(work.payload, work.target_compid);
3✔
910

911
    return true;
3✔
912
}
913

914
bool MavlinkFtpClient::remove_dir_start(Work& work, RemoveDirItem& item)
2✔
915
{
916
    if (item.path.length() + 1 >= max_data_length) {
2✔
917
        item.callback(ClientResult::InvalidParameter);
×
918
        return false;
×
919
    }
920

921
    work.last_opcode = CMD_REMOVE_DIRECTORY;
2✔
922
    work.payload = {};
2✔
923
    work.payload.seq_number = _last_sent_seq_number++;
2✔
924
    work.payload.session = _session;
2✔
925
    work.payload.opcode = work.last_opcode;
2✔
926
    work.payload.offset = 0;
2✔
927
    strncpy(reinterpret_cast<char*>(work.payload.data), item.path.c_str(), max_data_length - 1);
2✔
928
    work.payload.size = item.path.length() + 1;
2✔
929
    start_timer();
2✔
930

931
    send_mavlink_ftp_message(work.payload, work.target_compid);
2✔
932

933
    return true;
2✔
934
}
935

936
bool MavlinkFtpClient::compare_files_start(Work& work, CompareFilesItem& item)
3✔
937
{
938
    if (item.remote_path.length() + 1 >= max_data_length) {
3✔
939
        item.callback(ClientResult::InvalidParameter, false);
×
940
        return false;
×
941
    }
942

943
    auto result_local = calc_local_file_crc32(item.local_path, item.local_crc);
3✔
944
    if (result_local != ClientResult::Success) {
3✔
945
        item.callback(result_local, false);
×
946
        return false;
×
947
    }
948

949
    work.last_opcode = CMD_CALC_FILE_CRC32;
3✔
950
    work.payload = {};
3✔
951
    work.payload.seq_number = _last_sent_seq_number++;
3✔
952
    work.payload.session = _session;
3✔
953
    work.payload.opcode = work.last_opcode;
3✔
954
    work.payload.offset = 0;
3✔
955
    strncpy(
3✔
956
        reinterpret_cast<char*>(work.payload.data), item.remote_path.c_str(), max_data_length - 1);
3✔
957
    work.payload.size = item.remote_path.length() + 1;
3✔
958
    start_timer();
3✔
959

960
    send_mavlink_ftp_message(work.payload, work.target_compid);
3✔
961

962
    return true;
3✔
963
}
964

965
bool MavlinkFtpClient::list_dir_start(Work& work, ListDirItem& item)
2✔
966
{
967
    if (item.path.length() + 1 >= max_data_length) {
2✔
968
        item.callback(ClientResult::InvalidParameter, {}, {});
×
969
        return false;
×
970
    }
971

972
    work.last_opcode = CMD_LIST_DIRECTORY;
2✔
973
    work.payload = {};
2✔
974
    work.payload.seq_number = _last_sent_seq_number++;
2✔
975
    work.payload.session = _session;
2✔
976
    work.payload.opcode = work.last_opcode;
2✔
977
    work.payload.offset = 0;
2✔
978
    strncpy(reinterpret_cast<char*>(work.payload.data), item.path.c_str(), max_data_length - 1);
2✔
979
    work.payload.size = item.path.length() + 1;
2✔
980
    start_timer();
2✔
981

982
    send_mavlink_ftp_message(work.payload, work.target_compid);
2✔
983

984
    return true;
2✔
985
}
986

987
bool MavlinkFtpClient::list_dir_continue(Work& work, ListDirItem& item, PayloadHeader* payload)
9✔
988
{
989
    if (_debugging) {
9✔
990
        LogDebug() << "List dir response received, got " << (int)payload->size << " chars";
×
991
    }
992

993
    if (payload->size > max_data_length) {
9✔
994
        LogWarn() << "Received FTP payload with invalid size";
×
995
        return false;
×
996
    }
997

998
    if (payload->size == 0) {
9✔
999
        std::sort(item.dirs.begin(), item.dirs.end());
×
1000
        std::sort(item.files.begin(), item.files.end());
×
1001
        item.callback(ClientResult::Success, item.dirs, item.files);
×
1002
        return false;
×
1003
    }
1004

1005
    // Make sure there is a zero termination.
1006
    payload->data[payload->size - 1] = '\0';
9✔
1007

1008
    size_t i = 0;
9✔
1009
    while (i + 1 < payload->size) {
209✔
1010
        const int entry_len = std::strlen(reinterpret_cast<char*>(&payload->data[i]));
200✔
1011

1012
        std::string entry;
200✔
1013
        entry.resize(entry_len);
200✔
1014
        std::memcpy(entry.data(), &payload->data[i], entry_len);
200✔
1015

1016
        i += entry_len + 1;
200✔
1017

1018
        ++item.offset;
200✔
1019

1020
        if (entry[0] == 'S') {
200✔
1021
            // Skip skip for now
1022
            continue;
×
1023
        }
1024

1025
        auto tab = entry.find('\t');
200✔
1026
        if (tab != std::string::npos) {
200✔
1027
            entry = entry.substr(0, tab);
100✔
1028
        }
1029

1030
        if (entry[0] == 'D') {
200✔
1031
            item.dirs.push_back(entry.substr(1, entry.size() - 1));
100✔
1032
        } else if (entry[0] == 'F') {
100✔
1033
            item.files.push_back(entry.substr(1, entry.size() - 1));
100✔
1034
        } else {
1035
            LogErr() << "Unknown list_dir entry: " << entry;
×
1036
        }
1037
    }
200✔
1038

1039
    work.last_opcode = CMD_LIST_DIRECTORY;
9✔
1040
    work.payload = {};
9✔
1041
    work.payload.seq_number = _last_sent_seq_number++;
9✔
1042
    work.payload.session = _session;
9✔
1043
    work.payload.opcode = work.last_opcode;
9✔
1044
    work.payload.offset = item.offset;
9✔
1045
    strncpy(reinterpret_cast<char*>(work.payload.data), item.path.c_str(), max_data_length - 1);
9✔
1046
    work.payload.size = item.path.length() + 1;
9✔
1047
    start_timer();
9✔
1048

1049
    send_mavlink_ftp_message(work.payload, work.target_compid);
9✔
1050

1051
    return true;
9✔
1052
}
1053

1054
MavlinkFtpClient::ClientResult MavlinkFtpClient::result_from_nak(PayloadHeader* payload)
15✔
1055
{
1056
    ServerResult sr = static_cast<ServerResult>(payload->data[0]);
15✔
1057

1058
    // PX4 Mavlink FTP returns "File doesn't exist" this way
1059
    if (sr == ServerResult::ERR_FAIL_ERRNO && payload->data[1] == ENOENT) {
15✔
1060
        sr = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
1061
    }
1062

1063
    return translate(sr);
15✔
1064
}
1065

1066
MavlinkFtpClient::ClientResult MavlinkFtpClient::translate(ServerResult result)
15✔
1067
{
1068
    switch (result) {
15✔
1069
        case ServerResult::SUCCESS:
×
1070
            return ClientResult::Success;
×
1071
        case ServerResult::ERR_FAIL:
14✔
1072
            return ClientResult::ProtocolError;
14✔
1073
        case ServerResult::ERR_FAIL_ERRNO:
×
1074
            return ClientResult::ProtocolError;
×
1075
        case ServerResult::ERR_INVALID_DATA_SIZE:
×
1076
            return ClientResult::ProtocolError;
×
1077
        case ServerResult::ERR_INVALID_SESSION:
×
1078
            return ClientResult::ProtocolError;
×
1079
        case ServerResult::ERR_NO_SESSIONS_AVAILABLE:
×
1080
            return ClientResult::ProtocolError;
×
1081
        case ServerResult::ERR_EOF:
×
1082
            return ClientResult::ProtocolError;
×
1083
        case ServerResult::ERR_UNKOWN_COMMAND:
×
1084
            return ClientResult::Unsupported;
×
1085
        case ServerResult::ERR_FAIL_FILE_EXISTS:
×
1086
            return ClientResult::FileExists;
×
1087
        case ServerResult::ERR_FAIL_FILE_PROTECTED:
×
1088
            return ClientResult::FileProtected;
×
1089
        case ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST:
1✔
1090
            return ClientResult::FileDoesNotExist;
1✔
1091
        case ServerResult::ERR_TIMEOUT:
×
1092
            return ClientResult::Timeout;
×
1093
        case ServerResult::ERR_FILE_IO_ERROR:
×
1094
            return ClientResult::FileIoError;
×
1095
        default:
×
1096
            LogInfo() << "Unknown error code: " << (int)result;
×
1097
            return ClientResult::ProtocolError;
×
1098
    }
1099
}
1100

1101
void MavlinkFtpClient::download_async(
18✔
1102
    const std::string& remote_path,
1103
    const std::string& local_folder,
1104
    bool use_burst,
1105
    DownloadCallback callback,
1106
    std::optional<uint8_t> maybe_target_compid)
1107
{
1108
    if (use_burst) {
18✔
1109
        auto item = DownloadBurstItem{};
10✔
1110
        item.remote_path = remote_path;
10✔
1111
        item.local_folder = local_folder;
10✔
1112
        item.callback = callback;
10✔
1113
        auto new_work =
1114
            Work{std::move(item), maybe_target_compid.value_or(get_target_component_id())};
10✔
1115
        _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
10✔
1116

1117
    } else {
10✔
1118
        auto item = DownloadItem{};
8✔
1119
        item.remote_path = remote_path;
8✔
1120
        item.local_folder = local_folder;
8✔
1121
        item.callback = callback;
8✔
1122
        auto new_work =
1123
            Work{std::move(item), maybe_target_compid.value_or(get_target_component_id())};
8✔
1124
        _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
8✔
1125
    }
8✔
1126
}
18✔
1127

1128
void MavlinkFtpClient::upload_async(
7✔
1129
    const std::string& local_file_path, const std::string& remote_folder, UploadCallback callback)
1130
{
1131
    auto item = UploadItem{};
7✔
1132
    item.local_file_path = local_file_path;
7✔
1133
    item.remote_folder = remote_folder;
7✔
1134
    item.callback = callback;
7✔
1135
    auto new_work = Work{std::move(item), get_target_component_id()};
7✔
1136

1137
    _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
7✔
1138
}
7✔
1139

1140
void MavlinkFtpClient::list_directory_async(const std::string& path, ListDirectoryCallback callback)
2✔
1141
{
1142
    auto item = ListDirItem{};
2✔
1143
    item.path = path;
2✔
1144
    item.callback = callback;
2✔
1145
    auto new_work = Work{std::move(item), get_target_component_id()};
2✔
1146

1147
    _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
2✔
1148
}
2✔
1149

1150
void MavlinkFtpClient::create_directory_async(const std::string& path, ResultCallback callback)
3✔
1151
{
1152
    auto item = CreateDirItem{};
3✔
1153
    item.path = path;
3✔
1154
    item.callback = callback;
3✔
1155
    auto new_work = Work{std::move(item), get_target_component_id()};
3✔
1156

1157
    _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
3✔
1158
}
3✔
1159

1160
void MavlinkFtpClient::remove_directory_async(const std::string& path, ResultCallback callback)
2✔
1161
{
1162
    auto item = RemoveDirItem{};
2✔
1163
    item.path = path;
2✔
1164
    item.callback = callback;
2✔
1165
    auto new_work = Work{std::move(item), get_target_component_id()};
2✔
1166

1167
    _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
2✔
1168
}
2✔
1169

1170
void MavlinkFtpClient::remove_file_async(const std::string& path, ResultCallback callback)
4✔
1171
{
1172
    auto item = RemoveItem{};
4✔
1173
    item.path = path;
4✔
1174
    item.callback = callback;
4✔
1175
    auto new_work = Work{std::move(item), get_target_component_id()};
4✔
1176

1177
    _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
4✔
1178
}
4✔
1179

1180
void MavlinkFtpClient::rename_async(
2✔
1181
    const std::string& from_path, const std::string& to_path, ResultCallback callback)
1182
{
1183
    auto item = RenameItem{};
2✔
1184
    item.from_path = from_path;
2✔
1185
    item.to_path = to_path;
2✔
1186
    item.callback = callback;
2✔
1187
    auto new_work = Work{std::move(item), get_target_component_id()};
2✔
1188

1189
    _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
2✔
1190
}
2✔
1191

1192
void MavlinkFtpClient::are_files_identical_async(
3✔
1193
    const std::string& local_path,
1194
    const std::string& remote_path,
1195
    AreFilesIdenticalCallback callback)
1196
{
1197
    auto item = CompareFilesItem{};
3✔
1198
    item.local_path = local_path;
3✔
1199
    item.remote_path = remote_path;
3✔
1200
    item.callback = callback;
3✔
1201
    auto new_work = Work{std::move(item), get_target_component_id()};
3✔
1202

1203
    _work_queue.push_back(std::make_shared<Work>(std::move(new_work)));
3✔
1204
}
3✔
1205

1206
void MavlinkFtpClient::send_mavlink_ftp_message(const PayloadHeader& payload, uint8_t target_compid)
569✔
1207
{
1208
    if (_debugging) {
569✔
1209
        LogDebug() << "FTP send: opcode: " << (int)payload.opcode << ", seq: " << payload.seq_number
×
1210
                   << " to: " << (int)_system_impl.get_system_id() << "/" << (int)target_compid;
×
1211
    }
1212
    _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
569✔
1213
        mavlink_message_t message;
1214
        mavlink_msg_file_transfer_protocol_pack_chan(
1,138✔
1215
            mavlink_address.system_id,
569✔
1216
            mavlink_address.component_id,
569✔
1217
            channel,
1218
            &message,
1219
            _network_id,
569✔
1220
            _system_impl.get_system_id(),
569✔
1221
            target_compid,
569✔
1222
            reinterpret_cast<const uint8_t*>(&payload));
569✔
1223
        return message;
569✔
1224
    });
1225
}
569✔
1226

1227
void MavlinkFtpClient::start_timer(std::optional<double> duration_s)
817✔
1228
{
1229
    _system_impl.unregister_timeout_handler(_timeout_cookie);
817✔
1230
    _timeout_cookie = _system_impl.register_timeout_handler(
817✔
1231
        [this]() { timeout(); }, duration_s.value_or(_system_impl.timeout_s()));
900✔
1232
}
817✔
1233

1234
void MavlinkFtpClient::stop_timer()
213✔
1235
{
1236
    _system_impl.unregister_timeout_handler(_timeout_cookie);
213✔
1237
}
213✔
1238

1239
void MavlinkFtpClient::timeout()
83✔
1240
{
1241
    if (_debugging) {
83✔
1242
        LogDebug() << "Timeout!";
×
1243
    }
1244

1245
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
83✔
1246
    auto work = work_queue_guard.get_front();
83✔
1247
    if (!work) {
83✔
1248
        return;
×
1249
    }
1250

1251
    std::visit(
83✔
1252
        overloaded{
166✔
1253
            [&](DownloadItem& item) {
33✔
1254
                if (--work->retries == 0) {
33✔
1255
                    item.callback(ClientResult::Timeout, {});
1✔
1256
                    work_queue_guard.pop_front();
1✔
1257
                    return;
1✔
1258
                }
1259
                if (_debugging) {
32✔
1260
                    LogDebug() << "Retries left: " << work->retries;
×
1261
                }
1262

1263
                work->payload.seq_number = _last_sent_seq_number++;
32✔
1264
                start_timer();
32✔
1265
                send_mavlink_ftp_message(work->payload, work->target_compid);
32✔
1266
            },
1267
            [&](DownloadBurstItem& item) {
17✔
1268
                if (--work->retries == 0) {
17✔
1269
                    item.callback(ClientResult::Timeout, {});
1✔
1270
                    work_queue_guard.pop_front();
1✔
1271
                    return;
1✔
1272
                }
1273
                if (_debugging) {
16✔
1274
                    LogDebug() << "Retries left: " << work->retries;
×
1275
                }
1276

1277
                {
1278
                    // This happens when we missed the last ack containing burst complete.
1279
                    // We have already a file size, so we don't need to start at the
1280
                    // beginning any more.
1281
                    if (item.file_size != 0 && item.current_offset != 0) {
16✔
1282
                        // In that case start requesting what we missed.
1283
                        if (item.current_offset == item.file_size && item.missing_data.empty()) {
14✔
1284
                            // We are done anyway.
1285
                            item.ofstream.close();
1✔
1286
                            item.callback(ClientResult::Success, {});
1✔
1287
                            download_burst_end(*work);
1✔
1288
                            work_queue_guard.pop_front();
1✔
1289
                        } else {
1290
                            // The burst is supposedly complete but we still need data because
1291
                            // we missed some, so request next without burst.
1292
                            // We presumably missed the very last chunk.
1293
                            if (item.current_offset < item.file_size) {
13✔
1294
                                item.missing_data.emplace_back(DownloadBurstItem::MissingData{
2✔
1295
                                    item.current_offset, item.file_size - item.current_offset});
1✔
1296
                                item.current_offset = item.file_size;
1✔
1297
                                if (_debugging) {
1✔
1298
                                    LogDebug() << "Adding " << item.current_offset << " with size "
×
1299
                                               << item.file_size - item.current_offset;
×
1300
                                }
1301
                            }
1302
                            request_next_rest(*work, item);
13✔
1303
                        }
1304
                    } else {
1305
                        // Otherwise, start burst again.
1306
                        start_timer();
2✔
1307
                        send_mavlink_ftp_message(work->payload, work->target_compid);
2✔
1308
                    }
1309
                }
1310
            },
1311
            [&](UploadItem& item) {
33✔
1312
                if (--work->retries == 0) {
33✔
1313
                    item.callback(ClientResult::Timeout, {});
1✔
1314
                    work_queue_guard.pop_front();
1✔
1315
                    return;
1✔
1316
                }
1317
                if (_debugging) {
32✔
1318
                    LogDebug() << "Retries left: " << work->retries;
×
1319
                }
1320

1321
                work->payload.seq_number = _last_sent_seq_number++;
32✔
1322
                start_timer();
32✔
1323
                send_mavlink_ftp_message(work->payload, work->target_compid);
32✔
1324
            },
1325
            [&](RemoveItem& item) {
×
1326
                if (--work->retries == 0) {
×
1327
                    item.callback(ClientResult::Timeout);
×
1328
                    work_queue_guard.pop_front();
×
1329
                    return;
×
1330
                }
1331
                if (_debugging) {
×
1332
                    LogDebug() << "Retries left: " << work->retries;
×
1333
                }
1334

1335
                work->payload.seq_number = _last_sent_seq_number++;
×
1336
                start_timer();
×
1337
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1338
            },
1339
            [&](RenameItem& item) {
×
1340
                if (--work->retries == 0) {
×
1341
                    item.callback(ClientResult::Timeout);
×
1342
                    work_queue_guard.pop_front();
×
1343
                    return;
×
1344
                }
1345
                if (_debugging) {
×
1346
                    LogDebug() << "Retries left: " << work->retries;
×
1347
                }
1348

1349
                work->payload.seq_number = _last_sent_seq_number++;
×
1350
                start_timer();
×
1351
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1352
            },
1353
            [&](CreateDirItem& item) {
×
1354
                if (--work->retries == 0) {
×
1355
                    item.callback(ClientResult::Timeout);
×
1356
                    work_queue_guard.pop_front();
×
1357
                    return;
×
1358
                }
1359
                if (_debugging) {
×
1360
                    LogDebug() << "Retries left: " << work->retries;
×
1361
                }
1362

1363
                work->payload.seq_number = _last_sent_seq_number++;
×
1364
                start_timer();
×
1365
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1366
            },
1367
            [&](RemoveDirItem& item) {
×
1368
                if (--work->retries == 0) {
×
1369
                    item.callback(ClientResult::Timeout);
×
1370
                    work_queue_guard.pop_front();
×
1371
                    return;
×
1372
                }
1373
                if (_debugging) {
×
1374
                    LogDebug() << "Retries left: " << work->retries;
×
1375
                }
1376

1377
                work->payload.seq_number = _last_sent_seq_number++;
×
1378
                start_timer();
×
1379
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1380
            },
1381
            [&](CompareFilesItem& item) {
×
1382
                if (--work->retries == 0) {
×
1383
                    item.callback(ClientResult::Timeout, false);
×
1384
                    work_queue_guard.pop_front();
×
1385
                    return;
×
1386
                }
1387
                if (_debugging) {
×
1388
                    LogDebug() << "Retries left: " << work->retries;
×
1389
                }
1390

1391
                work->payload.seq_number = _last_sent_seq_number++;
×
1392
                start_timer();
×
1393
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1394
            },
1395
            [&](ListDirItem& item) {
×
1396
                if (--work->retries == 0) {
×
1397
                    item.callback(ClientResult::Timeout, {}, {});
×
1398
                    work_queue_guard.pop_front();
×
1399
                    return;
×
1400
                }
1401
                if (_debugging) {
×
1402
                    LogDebug() << "Retries left: " << work->retries;
×
1403
                }
1404

1405
                work->payload.seq_number = _last_sent_seq_number++;
×
1406
                start_timer();
×
1407
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1408
            }},
1409
        work->item);
83✔
1410
}
83✔
1411

1412
MavlinkFtpClient::ClientResult
1413
MavlinkFtpClient::calc_local_file_crc32(const std::string& path, uint32_t& csum)
3✔
1414
{
1415
    std::error_code ec;
3✔
1416
    if (!fs::exists(path, ec)) {
3✔
1417
        return ClientResult::FileDoesNotExist;
×
1418
    }
1419

1420
    std::ifstream stream(path, std::fstream::binary);
3✔
1421
    if (!stream) {
3✔
1422
        return ClientResult::FileIoError;
×
1423
    }
1424

1425
    // Read whole file in buffer size chunks
1426
    Crc32 checksum;
3✔
1427
    uint8_t buffer[4096];
1428
    std::streamsize bytes_read;
1429

1430
    do {
1431
        stream.read(reinterpret_cast<char*>(buffer), sizeof(buffer));
6✔
1432
        bytes_read = stream.gcount(); // Get the number of bytes actually read
6✔
1433
        checksum.add(reinterpret_cast<const uint8_t*>(buffer), bytes_read);
6✔
1434
    } while (bytes_read > 0);
6✔
1435

1436
    csum = checksum.get();
3✔
1437

1438
    return ClientResult::Success;
3✔
1439
}
3✔
1440

1441
void MavlinkFtpClient::terminate_session(Work& work)
21✔
1442
{
1443
    work.last_opcode = CMD_TERMINATE_SESSION;
21✔
1444

1445
    work.payload = {};
21✔
1446
    work.payload.seq_number = _last_sent_seq_number++;
21✔
1447
    work.payload.session = _session;
21✔
1448

1449
    work.payload.opcode = work.last_opcode;
21✔
1450
    work.payload.offset = 0;
21✔
1451
    work.payload.size = 0;
21✔
1452

1453
    send_mavlink_ftp_message(work.payload, work.target_compid);
21✔
1454
}
21✔
1455

1456
uint8_t MavlinkFtpClient::get_our_compid()
×
1457
{
1458
    return _system_impl.get_own_component_id();
×
1459
}
1460

1461
uint8_t MavlinkFtpClient::get_target_component_id()
41✔
1462
{
1463
    return _target_component_id_set ? _target_component_id : _system_impl.get_autopilot_id();
41✔
1464
}
1465

1466
MavlinkFtpClient::ClientResult MavlinkFtpClient::set_target_compid(uint8_t component_id)
×
1467
{
1468
    _target_component_id = component_id;
×
1469
    _target_component_id_set = true;
×
1470
    return ClientResult::Success;
×
1471
}
1472

1473
std::ostream& operator<<(std::ostream& str, MavlinkFtpClient::ClientResult const& result)
3✔
1474
{
1475
    switch (result) {
3✔
1476
        default:
×
1477
            // Fallthrough
1478
        case MavlinkFtpClient::ClientResult::Unknown:
1479
            return str << "Unknown";
×
1480
        case MavlinkFtpClient::ClientResult::Success:
3✔
1481
            return str << "Success";
3✔
1482
        case MavlinkFtpClient::ClientResult::Next:
×
1483
            return str << "Next";
×
1484
        case MavlinkFtpClient::ClientResult::Timeout:
×
1485
            return str << "Timeout";
×
1486
        case MavlinkFtpClient::ClientResult::Busy:
×
1487
            return str << "Busy";
×
1488
        case MavlinkFtpClient::ClientResult::FileIoError:
×
1489
            return str << "FileIoError";
×
1490
        case MavlinkFtpClient::ClientResult::FileExists:
×
1491
            return str << "FileExists";
×
1492
        case MavlinkFtpClient::ClientResult::FileDoesNotExist:
×
1493
            return str << "FileDoesNotExist";
×
1494
        case MavlinkFtpClient::ClientResult::FileProtected:
×
1495
            return str << "FileProtected";
×
1496
        case MavlinkFtpClient::ClientResult::InvalidParameter:
×
1497
            return str << "InvalidParameter";
×
1498
        case MavlinkFtpClient::ClientResult::Unsupported:
×
1499
            return str << "Unsupported";
×
1500
        case MavlinkFtpClient::ClientResult::ProtocolError:
×
1501
            return str << "ProtocolError";
×
1502
        case MavlinkFtpClient::ClientResult::NoSystem:
×
1503
            return str << "NoSystem";
×
1504
    }
1505
}
1506

1507
void MavlinkFtpClient::cancel_all_operations()
24✔
1508
{
1509
    // Stop any pending timeout timers
1510
    stop_timer();
24✔
1511

1512
    // Clear the work queue to cancel all pending operations
1513
    // This prevents callbacks from being executed
1514
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
24✔
1515
    while (work_queue_guard.get_front() != nullptr) {
24✔
1516
        work_queue_guard.pop_front();
×
1517
    }
1518
}
24✔
1519

1520
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc