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

mavlink / MAVSDK / 19729995407

27 Nov 2025 08:32AM UTC coverage: 48.224%. Remained the same
19729995407

Pull #2719

github

web-flow
Merge 37c9ed0d0 into 0267319f4
Pull Request #2719: CMake custom command fails in certain build configurations

17635 of 36569 relevant lines covered (48.22%)

466.93 hits per line

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

73.26
/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)
138✔
18
{
19
    if (const char* env_p = std::getenv("MAVSDK_FTP_DEBUGGING")) {
138✔
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(
138✔
27
        MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL,
28
        [this](const mavlink_message_t& message) { process_mavlink_ftp_message(message); },
1,239✔
29
        this);
30
}
138✔
31

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

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

42
    auto work = work_queue_guard.get_front();
17,276✔
43
    if (!work) {
17,311✔
44
        return;
16,521✔
45
    }
46

47
    if (work->started) {
903✔
48
        return;
862✔
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
}
34,852✔
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;
505✔
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
                       << ", size: " << (int)payload->size << ", offset: " << (int)payload->offset
×
134
                       << ", seq: " << payload->seq_number;
×
135
        }
136
    }
137

138
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
1,230✔
139

140
    auto work = work_queue_guard.get_front();
1,230✔
141
    if (!work) {
1,230✔
142
        return;
487✔
143
    }
144

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

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

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

178
                    } else {
179
                        LogWarn() << "Unexpected ack";
×
180
                    }
181

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

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

208
                    } else {
209
                        LogWarn() << "Unexpected ack";
×
210
                    }
211

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

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

248
                    } else {
249
                        LogWarn() << "Unexpected ack";
×
250
                    }
251

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

266
                    } else {
267
                        LogWarn() << "Unexpected ack";
×
268
                    }
269

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

284
                    } else {
285
                        LogWarn() << "Unexpected ack";
×
286
                    }
287

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

302
                    } else {
303
                        LogWarn() << "Unexpected ack";
×
304
                    }
305

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

320
                    } else {
321
                        LogWarn() << "Unexpected ack";
×
322
                    }
323

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

339
                    } else {
340
                        LogWarn() << "Unexpected ack";
×
341
                    }
342

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

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

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

379
    work->last_received_seq_number = payload->seq_number;
734✔
380
}
1,726✔
381

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

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

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

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

408
    start_timer();
8✔
409
    send_mavlink_ftp_message(work.payload, work.target_compid);
8✔
410

411
    return true;
8✔
412
}
8✔
413

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

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

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

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

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

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

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

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

464
        start_timer();
294✔
465
        send_mavlink_ftp_message(work.payload, work.target_compid);
294✔
466

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

473
        start_timer();
5✔
474
        terminate_session(work);
5✔
475
        return true;
5✔
476
    }
477

478
    return true;
479
}
480

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

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

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

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

506
    start_timer();
10✔
507
    send_mavlink_ftp_message(work.payload, work.target_compid);
10✔
508

509
    return true;
10✔
510
}
10✔
511

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

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

522
        request_burst(work, item);
8✔
523

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

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

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

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

562
        // Keep track of what was written.
563
        item.current_offset = payload->offset + payload->size;
270✔
564

565
        if (_debugging) {
270✔
566
            LogDebug() << "Received " << payload->offset << " to "
×
567
                       << payload->size + payload->offset;
×
568
        }
569

570
        if (payload->size + payload->offset >= item.file_size) {
270✔
571
            if (_debugging) {
6✔
572
                LogDebug() << "Burst complete";
×
573
            }
574

575
            if (item.missing_data.empty()) {
6✔
576
                // No missing data, we're done.
577

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

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

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

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

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

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

638
        // Check if this was the last one
639
        if (item.file_size == payload->offset + payload->size) {
9✔
640
            item.current_offset = item.file_size;
1✔
641
        }
642

643
        const size_t bytes_transferred = burst_bytes_transferred(item);
9✔
644

645
        if (_debugging) {
9✔
646
            LogDebug() << "Written " << bytes_transferred << " of " << item.file_size << " bytes";
×
647
        }
648

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

659
            request_next_rest(work, item);
8✔
660
        }
661

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

668
    return true;
287✔
669
}
670

671
void MavlinkFtpClient::download_burst_end(Work& work)
7✔
672
{
673
    work.last_opcode = CMD_TERMINATE_SESSION;
7✔
674

675
    work.payload = {};
7✔
676
    work.payload.seq_number = work.last_sent_seq_number++;
7✔
677
    work.payload.session = _session;
7✔
678

679
    work.payload.opcode = work.last_opcode;
7✔
680
    work.payload.offset = 0;
7✔
681
    work.payload.size = 0;
7✔
682

683
    start_timer();
7✔
684
    send_mavlink_ftp_message(work.payload, work.target_compid);
7✔
685
}
7✔
686

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

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

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

701
    start_timer();
8✔
702
    send_mavlink_ftp_message(work.payload, work.target_compid);
8✔
703
}
8✔
704

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

710
    if (_debugging) {
23✔
711
        LogDebug() << "Re-requesting from " << missing.offset << " with size " << size;
×
712
    }
713

714
    work.last_opcode = CMD_READ_FILE;
23✔
715
    work.payload = {};
23✔
716
    work.payload.seq_number = work.last_sent_seq_number++;
23✔
717
    work.payload.session = _session;
23✔
718
    work.payload.opcode = work.last_opcode;
23✔
719
    work.payload.offset = missing.offset;
23✔
720

721
    work.payload.size = size;
23✔
722

723
    start_timer();
23✔
724
    send_mavlink_ftp_message(work.payload, work.target_compid);
23✔
725
}
23✔
726

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

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

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

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

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

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

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

779
    start_timer();
7✔
780
    send_mavlink_ftp_message(work.payload, work.target_compid);
7✔
781

782
    return true;
7✔
783
}
7✔
784

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

790
        work.payload = {};
97✔
791
        work.payload.seq_number = work.last_sent_seq_number++;
97✔
792
        work.payload.session = _session;
97✔
793

794
        work.payload.opcode = work.last_opcode;
97✔
795
        work.payload.offset = item.bytes_transferred;
97✔
796

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

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

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

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

810
        work.payload.size = bytes_read;
97✔
811
        item.bytes_transferred += bytes_read;
97✔
812

813
        start_timer();
97✔
814
        send_mavlink_ftp_message(work.payload, work.target_compid);
97✔
815

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

820
        work.payload = {};
4✔
821
        work.payload.seq_number = work.last_sent_seq_number++;
4✔
822
        work.payload.session = _session;
4✔
823

824
        work.payload.opcode = work.last_opcode;
4✔
825
        work.payload.offset = 0;
4✔
826
        work.payload.size = 0;
4✔
827

828
        start_timer();
4✔
829
        send_mavlink_ftp_message(work.payload, work.target_compid);
4✔
830
    }
831

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

837
    return true;
101✔
838
}
839

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

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

856
    start_timer();
4✔
857
    send_mavlink_ftp_message(work.payload, work.target_compid);
4✔
858

859
    return true;
4✔
860
}
861

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

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

885
    send_mavlink_ftp_message(work.payload, work.target_compid);
2✔
886

887
    return true;
2✔
888
}
889

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

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

907
    send_mavlink_ftp_message(work.payload, work.target_compid);
3✔
908

909
    return true;
3✔
910
}
911

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

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

929
    send_mavlink_ftp_message(work.payload, work.target_compid);
2✔
930

931
    return true;
2✔
932
}
933

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

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

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

958
    send_mavlink_ftp_message(work.payload, work.target_compid);
3✔
959

960
    return true;
3✔
961
}
962

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

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

980
    send_mavlink_ftp_message(work.payload, work.target_compid);
2✔
981

982
    return true;
2✔
983
}
984

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

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

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

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

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

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

1014
        i += entry_len + 1;
200✔
1015

1016
        ++item.offset;
200✔
1017

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

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

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

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

1047
    send_mavlink_ftp_message(work.payload, work.target_compid);
9✔
1048

1049
    return true;
9✔
1050
}
1051

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

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

1061
    return translate(sr);
15✔
1062
}
1063

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1204
void MavlinkFtpClient::send_mavlink_ftp_message(const PayloadHeader& payload, uint8_t target_compid)
569✔
1205
{
1206
    _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
569✔
1207
        mavlink_message_t message;
1208
        mavlink_msg_file_transfer_protocol_pack_chan(
1,138✔
1209
            mavlink_address.system_id,
569✔
1210
            mavlink_address.component_id,
569✔
1211
            channel,
1212
            &message,
1213
            _network_id,
569✔
1214
            _system_impl.get_system_id(),
569✔
1215
            target_compid,
569✔
1216
            reinterpret_cast<const uint8_t*>(&payload));
569✔
1217
        return message;
569✔
1218
    });
1219
}
569✔
1220

1221
void MavlinkFtpClient::start_timer(std::optional<double> duration_s)
817✔
1222
{
1223
    _system_impl.unregister_timeout_handler(_timeout_cookie);
817✔
1224
    _timeout_cookie = _system_impl.register_timeout_handler(
817✔
1225
        [this]() { timeout(); }, duration_s.value_or(_system_impl.timeout_s()));
900✔
1226
}
817✔
1227

1228
void MavlinkFtpClient::stop_timer()
200✔
1229
{
1230
    _system_impl.unregister_timeout_handler(_timeout_cookie);
200✔
1231
}
200✔
1232

1233
void MavlinkFtpClient::timeout()
83✔
1234
{
1235
    if (_debugging) {
83✔
1236
        LogDebug() << "Timeout!";
×
1237
    }
1238

1239
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
83✔
1240
    auto work = work_queue_guard.get_front();
83✔
1241
    if (!work) {
83✔
1242
        return;
×
1243
    }
1244

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

1257
                start_timer();
32✔
1258
                send_mavlink_ftp_message(work->payload, work->target_compid);
32✔
1259
            },
1260
            [&](DownloadBurstItem& item) {
16✔
1261
                if (--work->retries == 0) {
16✔
1262
                    item.callback(ClientResult::Timeout, {});
1✔
1263
                    work_queue_guard.pop_front();
1✔
1264
                    return;
1✔
1265
                }
1266
                if (_debugging) {
15✔
1267
                    LogDebug() << "Retries left: " << work->retries;
×
1268
                }
1269

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

1314
                start_timer();
33✔
1315
                send_mavlink_ftp_message(work->payload, work->target_compid);
33✔
1316
            },
1317
            [&](RemoveItem& item) {
×
1318
                if (--work->retries == 0) {
×
1319
                    item.callback(ClientResult::Timeout);
×
1320
                    work_queue_guard.pop_front();
×
1321
                    return;
×
1322
                }
1323
                if (_debugging) {
×
1324
                    LogDebug() << "Retries left: " << work->retries;
×
1325
                }
1326

1327
                start_timer();
×
1328
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1329
            },
1330
            [&](RenameItem& item) {
×
1331
                if (--work->retries == 0) {
×
1332
                    item.callback(ClientResult::Timeout);
×
1333
                    work_queue_guard.pop_front();
×
1334
                    return;
×
1335
                }
1336
                if (_debugging) {
×
1337
                    LogDebug() << "Retries left: " << work->retries;
×
1338
                }
1339

1340
                start_timer();
×
1341
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1342
            },
1343
            [&](CreateDirItem& item) {
×
1344
                if (--work->retries == 0) {
×
1345
                    item.callback(ClientResult::Timeout);
×
1346
                    work_queue_guard.pop_front();
×
1347
                    return;
×
1348
                }
1349
                if (_debugging) {
×
1350
                    LogDebug() << "Retries left: " << work->retries;
×
1351
                }
1352

1353
                start_timer();
×
1354
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1355
            },
1356
            [&](RemoveDirItem& item) {
×
1357
                if (--work->retries == 0) {
×
1358
                    item.callback(ClientResult::Timeout);
×
1359
                    work_queue_guard.pop_front();
×
1360
                    return;
×
1361
                }
1362
                if (_debugging) {
×
1363
                    LogDebug() << "Retries left: " << work->retries;
×
1364
                }
1365

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

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

1392
                start_timer();
×
1393
                send_mavlink_ftp_message(work->payload, work->target_compid);
×
1394
            }},
1395
        work->item);
83✔
1396
}
83✔
1397

1398
MavlinkFtpClient::ClientResult
1399
MavlinkFtpClient::calc_local_file_crc32(const std::string& path, uint32_t& csum)
3✔
1400
{
1401
    std::error_code ec;
3✔
1402
    if (!fs::exists(path, ec)) {
3✔
1403
        return ClientResult::FileDoesNotExist;
×
1404
    }
1405

1406
    std::ifstream stream(path, std::fstream::binary);
3✔
1407
    if (!stream) {
3✔
1408
        return ClientResult::FileIoError;
×
1409
    }
1410

1411
    // Read whole file in buffer size chunks
1412
    Crc32 checksum;
3✔
1413
    uint8_t buffer[4096];
1414
    std::streamsize bytes_read;
1415

1416
    do {
1417
        stream.read(reinterpret_cast<char*>(buffer), sizeof(buffer));
6✔
1418
        bytes_read = stream.gcount(); // Get the number of bytes actually read
6✔
1419
        checksum.add(reinterpret_cast<const uint8_t*>(buffer), bytes_read);
6✔
1420
    } while (bytes_read > 0);
6✔
1421

1422
    csum = checksum.get();
3✔
1423

1424
    return ClientResult::Success;
3✔
1425
}
3✔
1426

1427
void MavlinkFtpClient::terminate_session(Work& work)
21✔
1428
{
1429
    work.last_opcode = CMD_TERMINATE_SESSION;
21✔
1430

1431
    work.payload = {};
21✔
1432
    work.payload.seq_number = work.last_sent_seq_number++;
21✔
1433
    work.payload.session = _session;
21✔
1434

1435
    work.payload.opcode = work.last_opcode;
21✔
1436
    work.payload.offset = 0;
21✔
1437
    work.payload.size = 0;
21✔
1438

1439
    send_mavlink_ftp_message(work.payload, work.target_compid);
21✔
1440
}
21✔
1441

1442
uint8_t MavlinkFtpClient::get_our_compid()
×
1443
{
1444
    return _system_impl.get_own_component_id();
×
1445
}
1446

1447
uint8_t MavlinkFtpClient::get_target_component_id()
41✔
1448
{
1449
    return _target_component_id_set ? _target_component_id : _system_impl.get_autopilot_id();
41✔
1450
}
1451

1452
MavlinkFtpClient::ClientResult MavlinkFtpClient::set_target_compid(uint8_t component_id)
×
1453
{
1454
    _target_component_id = component_id;
×
1455
    _target_component_id_set = true;
×
1456
    return ClientResult::Success;
×
1457
}
1458

1459
std::ostream& operator<<(std::ostream& str, MavlinkFtpClient::ClientResult const& result)
3✔
1460
{
1461
    switch (result) {
3✔
1462
        default:
×
1463
            // Fallthrough
1464
        case MavlinkFtpClient::ClientResult::Unknown:
1465
            return str << "Unknown";
×
1466
        case MavlinkFtpClient::ClientResult::Success:
3✔
1467
            return str << "Success";
3✔
1468
        case MavlinkFtpClient::ClientResult::Next:
×
1469
            return str << "Next";
×
1470
        case MavlinkFtpClient::ClientResult::Timeout:
×
1471
            return str << "Timeout";
×
1472
        case MavlinkFtpClient::ClientResult::Busy:
×
1473
            return str << "Busy";
×
1474
        case MavlinkFtpClient::ClientResult::FileIoError:
×
1475
            return str << "FileIoError";
×
1476
        case MavlinkFtpClient::ClientResult::FileExists:
×
1477
            return str << "FileExists";
×
1478
        case MavlinkFtpClient::ClientResult::FileDoesNotExist:
×
1479
            return str << "FileDoesNotExist";
×
1480
        case MavlinkFtpClient::ClientResult::FileProtected:
×
1481
            return str << "FileProtected";
×
1482
        case MavlinkFtpClient::ClientResult::InvalidParameter:
×
1483
            return str << "InvalidParameter";
×
1484
        case MavlinkFtpClient::ClientResult::Unsupported:
×
1485
            return str << "Unsupported";
×
1486
        case MavlinkFtpClient::ClientResult::ProtocolError:
×
1487
            return str << "ProtocolError";
×
1488
        case MavlinkFtpClient::ClientResult::NoSystem:
×
1489
            return str << "NoSystem";
×
1490
    }
1491
}
1492

1493
void MavlinkFtpClient::cancel_all_operations()
24✔
1494
{
1495
    // Stop any pending timeout timers
1496
    stop_timer();
24✔
1497

1498
    // Clear the work queue to cancel all pending operations
1499
    // This prevents callbacks from being executed
1500
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
24✔
1501
    while (work_queue_guard.get_front() != nullptr) {
24✔
1502
        work_queue_guard.pop_front();
×
1503
    }
1504
}
24✔
1505

1506
} // 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

© 2025 Coveralls, Inc