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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

61.41
/src/mavsdk/core/mavlink_ftp_server.cpp
1
#include <algorithm>
2
#include <fstream>
3
#include <filesystem>
4
#include <future>
5

6
#include "mavlink_ftp_server.h"
7
#include "server_component_impl.h"
8
#include "unused.h"
9
#include "crc32.h"
10

11
namespace mavsdk {
12

13
namespace fs = std::filesystem;
14

15
MavlinkFtpServer::MavlinkFtpServer(ServerComponentImpl& server_component_impl) :
72✔
16
    _server_component_impl(server_component_impl)
72✔
17
{
18
    if (const char* env_p = std::getenv("MAVSDK_FTP_DEBUGGING")) {
72✔
19
        if (std::string(env_p) == "1") {
×
20
            LogDebug() << "Ftp debugging is on.";
×
21
            _debugging = true;
×
22
        }
23
    }
24

25
    _server_component_impl.register_mavlink_message_handler(
72✔
26
        MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL,
27
        [this](const mavlink_message_t& message) { process_mavlink_ftp_message(message); },
1,174✔
28
        this);
29
}
72✔
30

31
void MavlinkFtpServer::process_mavlink_ftp_message(const mavlink_message_t& msg)
1,174✔
32
{
33
    // TODO: implement stream sending
34
    bool stream_send = false;
1,174✔
35
    UNUSED(stream_send);
1,174✔
36

37
    mavlink_file_transfer_protocol_t ftp_req;
1,174✔
38
    mavlink_msg_file_transfer_protocol_decode(&msg, &ftp_req);
1,174✔
39

40
    if (_debugging) {
1,174✔
41
        LogDebug() << "Processing FTP message to target compid: "
×
42
                   << std::to_string(ftp_req.target_component) << ", our compid: "
×
43
                   << std::to_string(_server_component_impl.get_own_component_id());
×
44
    }
45

46
    if (ftp_req.target_system != 0 &&
2,348✔
47
        ftp_req.target_system != _server_component_impl.get_own_system_id()) {
1,174✔
48
        LogWarn() << "wrong sysid!";
×
49
        return;
×
50
    }
51

52
    if (ftp_req.target_component != 0 &&
2,348✔
53
        ftp_req.target_component != _server_component_impl.get_own_component_id()) {
1,174✔
54
        LogWarn() << "wrong compid!";
9✔
55
        return;
9✔
56
    }
57

58
    const PayloadHeader& payload = *reinterpret_cast<PayloadHeader*>(&ftp_req.payload[0]);
1,165✔
59

60
    // Basic sanity check: validate length before use.
61
    if (payload.size > max_data_length) {
1,165✔
62
        auto response = PayloadHeader{};
×
63
        response.seq_number = payload.seq_number + 1;
×
64
        response.req_opcode = payload.opcode;
×
65
        response.opcode = Opcode::RSP_NAK;
×
66
        response.data[0] = ServerResult::ERR_INVALID_DATA_SIZE;
×
67
        response.size = 1;
×
68
        _send_mavlink_ftp_message(response);
×
69

70
    } else {
71
        if (_debugging) {
1,165✔
72
            LogDebug() << "FTP opcode: " << (int)payload.opcode << ", size: " << (int)payload.size
×
73
                       << ", offset: " << (int)payload.offset << ", seq: " << payload.seq_number;
×
74
        }
75

76
        _target_system_id = msg.sysid;
1,165✔
77
        _target_component_id = msg.compid;
1,165✔
78

79
        switch (payload.opcode) {
1,165✔
80
            case Opcode::CMD_NONE:
×
81
                if (_debugging) {
×
82
                    LogDebug() << "OPC:CMD_NONE";
×
83
                }
84
                break;
×
85

86
            case Opcode::CMD_TERMINATE_SESSION:
31✔
87
                if (_debugging) {
31✔
88
                    LogDebug() << "OPC:CMD_TERMINATE_SESSION";
×
89
                }
90
                _work_terminate(payload);
31✔
91
                break;
31✔
92

93
            case Opcode::CMD_RESET_SESSIONS:
×
94
                if (_debugging) {
×
95
                    LogDebug() << "OPC:CMD_RESET_SESSIONS";
×
96
                }
97
                _work_reset(payload);
×
98
                break;
×
99

100
            case Opcode::CMD_LIST_DIRECTORY:
11✔
101
                if (_debugging) {
11✔
102
                    LogDebug() << "OPC:CMD_LIST_DIRECTORY";
×
103
                }
104
                _work_list(payload);
11✔
105
                break;
11✔
106

107
            case Opcode::CMD_OPEN_FILE_RO:
17✔
108
                if (_debugging) {
17✔
109
                    LogDebug() << "OPC:CMD_OPEN_FILE_RO";
×
110
                }
111
                _work_open_file_readonly(payload);
17✔
112
                break;
17✔
113

114
            case Opcode::CMD_CREATE_FILE:
7✔
115
                if (_debugging) {
7✔
116
                    LogDebug() << "OPC:CMD_CREATE_FILE";
×
117
                }
118
                _work_create_file(payload);
7✔
119
                break;
7✔
120

121
            case Opcode::CMD_OPEN_FILE_WO:
×
122
                if (_debugging) {
×
123
                    LogDebug() << "OPC:CMD_OPEN_FILE_WO";
×
124
                }
125
                _work_open_file_writeonly(payload);
×
126
                break;
×
127

128
            case Opcode::CMD_READ_FILE:
272✔
129
                if (_debugging) {
272✔
130
                    LogDebug() << "OPC:CMD_READ_FILE";
×
131
                }
132
                _work_read(payload);
272✔
133
                break;
272✔
134

135
            case Opcode::CMD_BURST_READ_FILE:
8✔
136
                if (_debugging) {
8✔
137
                    LogDebug() << "OPC:CMD_BURST_READ_FILE";
×
138
                }
139
                _work_burst(payload);
8✔
140
                break;
8✔
141

142
            case Opcode::CMD_WRITE_FILE:
95✔
143
                if (_debugging) {
95✔
144
                    LogDebug() << "OPC:CMD_WRITE_FILE";
×
145
                }
146
                _work_write(payload);
95✔
147
                break;
95✔
148

149
            case Opcode::CMD_REMOVE_FILE:
4✔
150
                if (_debugging) {
4✔
151
                    LogDebug() << "OPC:CMD_REMOVE_FILE";
×
152
                }
153
                _work_remove_file(payload);
4✔
154
                break;
4✔
155

156
            case Opcode::CMD_RENAME:
2✔
157
                if (_debugging) {
2✔
158
                    LogDebug() << "OPC:CMD_RENAME";
×
159
                }
160
                _work_rename(payload);
2✔
161
                break;
2✔
162

163
            case Opcode::CMD_CREATE_DIRECTORY:
3✔
164
                if (_debugging) {
3✔
165
                    LogDebug() << "OPC:CMD_CREATE_DIRECTORY";
×
166
                }
167
                _work_create_directory(payload);
3✔
168
                break;
3✔
169

170
            case Opcode::CMD_REMOVE_DIRECTORY:
2✔
171
                if (_debugging) {
2✔
172
                    LogDebug() << "OPC:CMD_REMOVE_DIRECTORY";
×
173
                }
174
                _work_remove_directory(payload);
2✔
175
                break;
2✔
176

177
            case Opcode::CMD_CALC_FILE_CRC32:
3✔
178
                if (_debugging) {
3✔
179
                    LogDebug() << "OPC:CMD_CALC_FILE_CRC32";
×
180
                }
181
                _work_calc_file_CRC32(payload);
3✔
182
                break;
3✔
183

184
            default:
710✔
185
                // Not for us, ignore it.
186
                return;
710✔
187
        }
188
    }
189
}
190

191
MavlinkFtpServer::~MavlinkFtpServer()
72✔
192
{
193
    _server_component_impl.unregister_all_mavlink_message_handlers(this);
72✔
194

195
    std::lock_guard<std::mutex> lock(_mutex);
72✔
196
    _reset();
72✔
197
}
144✔
198

199
void MavlinkFtpServer::_send_mavlink_ftp_message(const PayloadHeader& payload)
729✔
200
{
201
    if (uint8_t(payload.opcode) == 0) {
729✔
202
        abort();
×
203
    }
204

205
    _server_component_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
729✔
206
        mavlink_message_t message;
207
        mavlink_msg_file_transfer_protocol_pack_chan(
729✔
208
            mavlink_address.system_id,
729✔
209
            mavlink_address.component_id,
729✔
210
            channel,
211
            &message,
212
            _network_id,
729✔
213
            _target_system_id,
729✔
214
            _target_component_id,
729✔
215
            reinterpret_cast<const uint8_t*>(&payload));
729✔
216
        return message;
729✔
217
    });
218
}
729✔
219

220
std::string MavlinkFtpServer::_data_as_string(const PayloadHeader& payload, size_t entry)
74✔
221
{
222
    size_t start = 0;
74✔
223
    size_t end = 0;
74✔
224
    std::string result;
74✔
225

226
    for (int i = entry; i >= 0; --i) {
149✔
227
        start = end;
75✔
228
        end +=
75✔
229
            strnlen(reinterpret_cast<const char*>(&payload.data[start]), max_data_length - start) +
75✔
230
            1;
231
    }
232

233
    result.resize(end - start);
74✔
234
    std::memcpy(result.data(), &payload.data[start], end - start);
74✔
235

236
    return result;
74✔
237
}
238

239
std::variant<std::string, MavlinkFtpServer::ServerResult>
240
MavlinkFtpServer::_path_from_payload(const PayloadHeader& payload, size_t entry)
50✔
241
{
242
    // Requires lock
243

244
    auto data = _data_as_string(payload, entry);
50✔
245
    return _path_from_string(data);
50✔
246
}
50✔
247

248
std::variant<std::string, MavlinkFtpServer::ServerResult>
249
MavlinkFtpServer::_path_from_string(const std::string& payload_path)
50✔
250
{
251
    // Requires lock
252

253
    // No permission whatsoever if the root dir is not set.
254
    if (_root_dir.empty()) {
50✔
255
        return ServerResult::ERR_FAIL;
9✔
256
    }
257

258
    // Take a copy before we mess with it.
259
    auto temp_path = payload_path;
41✔
260

261
    // We strip leading slashes (like absolute paths).
262
    if (temp_path.size() >= 1 && temp_path[0] == '/') {
41✔
263
        temp_path = temp_path.substr(1, temp_path.size());
×
264
    }
265

266
    fs::path combined_path = (fs::path(_root_dir) / temp_path).lexically_normal();
164✔
267

268
    // Check whether the combined path is inside the root dir.
269
    // From: https://stackoverflow.com/a/61125335/8548472
270
    auto ret = std::mismatch(_root_dir.begin(), _root_dir.end(), combined_path.string().begin());
41✔
271
    if (ret.first != _root_dir.end()) {
41✔
272
        LogWarn() << "Not inside root dir: " << combined_path.string()
12✔
273
                  << ", root dir: " << _root_dir;
12✔
274
        return ServerResult::ERR_FAIL;
4✔
275
    }
276

277
    return combined_path.string();
37✔
278
}
41✔
279

280
void MavlinkFtpServer::set_root_directory(const std::string& root_dir)
25✔
281
{
282
    std::lock_guard<std::mutex> lock(_mutex);
25✔
283

284
    std::error_code ignored;
25✔
285
    _root_dir = fs::canonical(fs::path(root_dir), ignored).string();
25✔
286
    if (_debugging) {
25✔
287
        LogDebug() << "Set root dir to: " << _root_dir;
×
288
    }
289
}
25✔
290

291
void MavlinkFtpServer::_work_list(const PayloadHeader& payload)
11✔
292
{
293
    auto response = PayloadHeader{};
11✔
294
    response.seq_number = payload.seq_number + 1;
11✔
295
    response.req_opcode = payload.opcode;
11✔
296

297
    std::lock_guard<std::mutex> lock(_mutex);
11✔
298

299
    auto maybe_path = _path_from_payload(payload);
11✔
300
    if (std::holds_alternative<ServerResult>(maybe_path)) {
11✔
301
        response.opcode = Opcode::RSP_NAK;
1✔
302
        response.size = 1;
1✔
303
        response.data[0] = std::get<ServerResult>(maybe_path);
1✔
304
        _send_mavlink_ftp_message(response);
1✔
305
        return;
1✔
306
    }
307

308
    fs::path path = std::get<std::string>(maybe_path);
10✔
309

310
    uint8_t offset = 0;
10✔
311

312
    // Move to the requested offset
313
    uint32_t requested_offset = payload.offset;
10✔
314

315
    std::error_code ec;
10✔
316
    if (!fs::exists(path, ec)) {
10✔
317
        LogWarn() << "FTP: can't open path " << path;
×
318
        // this is not an FTP error, abort directory by simulating eof
319
        response.opcode = Opcode::RSP_NAK;
×
320
        response.size = 1;
×
321
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
322
        _send_mavlink_ftp_message(response);
×
323
        return;
×
324
    }
325

326
    if (_debugging) {
10✔
327
        LogDebug() << "Opening path: " << path.string();
×
328
    }
329

330
    for (const auto& entry : fs::directory_iterator(fs::canonical(path))) {
1,248✔
331
        if (requested_offset > 0) {
1,226✔
332
            requested_offset--;
1,018✔
333
            continue;
1,018✔
334
        }
335
        const auto name = entry.path().filename();
208✔
336

337
        std::string payload_str;
208✔
338

339
        const auto is_regular_file = entry.is_regular_file(ec);
208✔
340
        if (ec) {
208✔
341
            LogWarn() << "Could not determine whether '" << entry.path().string()
×
342
                      << "' is a file: " << ec.message();
×
343
            continue;
×
344
        }
345

346
        const auto is_directory = entry.is_directory(ec);
208✔
347
        if (ec) {
208✔
348
            LogWarn() << "Could not determine whether '" << entry.path().string()
×
349
                      << "' is a directory: " << ec.message();
×
350
            continue;
×
351
        }
352

353
        if (is_regular_file) {
208✔
354
            const auto filesize = fs::file_size(entry.path(), ec);
104✔
355
            if (ec) {
104✔
356
                LogWarn() << "Could not get file size of '" << entry.path().string()
×
357
                          << "': " << ec.message();
×
358
                continue;
×
359
            }
360

361
            if (_debugging) {
104✔
362
                LogDebug() << "Found file: " << name.string() << ", size: " << filesize << " bytes";
×
363
            }
364

365
            payload_str += 'F';
104✔
366
            payload_str += name.string();
104✔
367
            payload_str += '\t';
104✔
368
            payload_str += std::to_string(filesize);
104✔
369

370
        } else if (is_directory) {
104✔
371
            if (_debugging) {
104✔
372
                LogDebug() << "Found directory: " << name.string();
×
373
            }
374

375
            payload_str += 'D';
104✔
376
            payload_str += name.string();
104✔
377

378
        } else {
379
            // Ignore all other types.
380
            continue;
×
381
        }
382

383
        auto required_len = payload_str.length() + 1;
208✔
384

385
        // Do we have room for the dir entry and the null terminator?
386
        if (offset + required_len > max_data_length) {
208✔
387
            break;
8✔
388
        }
389

390
        std::memcpy(&response.data[offset], payload_str.c_str(), required_len);
200✔
391

392
        offset += static_cast<uint8_t>(required_len);
200✔
393
    }
226✔
394

395
    if (offset == 0) {
10✔
396
        // We are done and need to respond with EOF.
397
        response.opcode = Opcode::RSP_NAK;
1✔
398
        response.size = 1;
1✔
399
        response.data[0] = ServerResult::ERR_EOF;
1✔
400

401
    } else {
402
        response.opcode = Opcode::RSP_ACK;
9✔
403
        response.size = offset;
9✔
404
    }
405

406
    _send_mavlink_ftp_message(response);
10✔
407
}
12✔
408

409
void MavlinkFtpServer::_work_open_file_readonly(const PayloadHeader& payload)
17✔
410
{
411
    auto response = PayloadHeader{};
17✔
412
    response.seq_number = payload.seq_number + 1;
17✔
413
    response.req_opcode = payload.opcode;
17✔
414

415
    std::lock_guard<std::mutex> lock(_mutex);
17✔
416
    if (_session_info.ifstream.is_open()) {
17✔
417
        _reset();
2✔
418
    }
419

420
    std::string path;
17✔
421
    {
422
        std::lock_guard<std::mutex> tmp_lock(_tmp_files_mutex);
17✔
423
        const auto it = _tmp_files.find(_data_as_string(payload));
17✔
424
        if (it != _tmp_files.end()) {
17✔
425
            path = it->second;
×
426
        } else {
427
            auto maybe_path = _path_from_payload(payload);
17✔
428
            if (std::holds_alternative<ServerResult>(maybe_path)) {
17✔
429
                response.opcode = Opcode::RSP_NAK;
4✔
430
                response.size = 1;
4✔
431
                response.data[0] = std::get<ServerResult>(maybe_path);
4✔
432
                _send_mavlink_ftp_message(response);
4✔
433
                return;
4✔
434
            }
435

436
            path = std::get<std::string>(maybe_path);
13✔
437
        }
17✔
438
    }
17✔
439

440
    if (_debugging) {
13✔
441
        LogInfo() << "Finding " << path << " in " << _root_dir;
×
442
    }
443
    if (path.rfind(_root_dir, 0) != 0) {
13✔
444
        LogWarn() << "FTP: invalid path " << path;
×
445
        response.opcode = Opcode::RSP_NAK;
×
446
        response.size = 1;
×
447
        response.data[0] = ServerResult::ERR_FAIL;
×
448
        _send_mavlink_ftp_message(response);
×
449
        return;
×
450
    }
451

452
    if (_debugging) {
13✔
453
        LogDebug() << "Going to open readonly: " << path;
×
454
    }
455

456
    std::error_code ec;
13✔
457
    if (!fs::exists(path, ec)) {
13✔
458
        LogErr() << "FTP: Open failed - file doesn't exist";
×
459
        response.opcode = Opcode::RSP_NAK;
×
460
        response.size = 1;
×
461
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
462
        _send_mavlink_ftp_message(response);
×
463
        return;
×
464
    }
465

466
    auto file_size = static_cast<uint32_t>(fs::file_size(path, ec));
13✔
467
    if (ec) {
13✔
468
        LogErr() << "Could not determine file size of '" << path << "': " << ec.message();
×
469
        return;
×
470
    }
471

472
    if (_debugging) {
13✔
473
        LogDebug() << "Determined filesize to be: " << file_size << " bytes";
×
474
    }
475

476
    std::ifstream ifstream;
13✔
477
    ifstream.open(path, std::ios::in | std::ios::binary);
13✔
478

479
    if (!ifstream.is_open()) {
13✔
480
        LogWarn() << "FTP: Open failed";
×
481
        response.opcode = Opcode::RSP_NAK;
×
482
        response.size = 1;
×
483
        response.data[0] = ServerResult::ERR_FAIL;
×
484
        _send_mavlink_ftp_message(response);
×
485
        return;
×
486
    }
487

488
    _session_info.ifstream = std::move(ifstream);
13✔
489
    _session_info.file_size = file_size;
13✔
490

491
    response.opcode = Opcode::RSP_ACK;
13✔
492
    response.session = 0;
13✔
493
    response.seq_number = payload.seq_number + 1;
13✔
494
    response.size = sizeof(uint32_t);
13✔
495
    std::memcpy(response.data, &file_size, response.size);
13✔
496

497
    _send_mavlink_ftp_message(response);
13✔
498
}
21✔
499

500
void MavlinkFtpServer::_work_open_file_writeonly(const PayloadHeader& payload)
×
501
{
502
    auto response = PayloadHeader{};
×
503
    response.seq_number = payload.seq_number + 1;
×
504
    response.req_opcode = payload.opcode;
×
505

506
    std::lock_guard<std::mutex> lock(_mutex);
×
507

508
    if (_session_info.ofstream.is_open()) {
×
509
        _reset();
×
510
    }
511

512
    std::string path;
×
513
    {
514
        std::lock_guard<std::mutex> tmp_lock(_tmp_files_mutex);
×
515
        const auto it = _tmp_files.find(_data_as_string(payload));
×
516
        if (it != _tmp_files.end()) {
×
517
            path = it->second;
×
518
        } else {
519
            auto maybe_path = _path_from_payload(payload);
×
520
            if (std::holds_alternative<ServerResult>(maybe_path)) {
×
521
                response.opcode = Opcode::RSP_NAK;
×
522
                response.size = 1;
×
523
                response.data[0] = std::get<ServerResult>(maybe_path);
×
524
                _send_mavlink_ftp_message(response);
×
525
                return;
×
526
            }
527

528
            path = std::get<std::string>(maybe_path);
×
529
        }
×
530
    }
×
531

532
    if (path.empty()) {
×
533
        response.opcode = Opcode::RSP_NAK;
×
534
        response.size = 1;
×
535
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
536
        _send_mavlink_ftp_message(response);
×
537
        return;
×
538
    }
539

540
    if (_debugging) {
×
541
        LogDebug() << "Finding " << path << " in " << _root_dir;
×
542
    }
543
    if (path.rfind(_root_dir, 0) != 0) {
×
544
        LogWarn() << "FTP: invalid path " << path;
×
545
        response.opcode = Opcode::RSP_NAK;
×
546
        response.size = 1;
×
547
        response.data[0] = ServerResult::ERR_FAIL;
×
548
        _send_mavlink_ftp_message(response);
×
549
        return;
×
550
    }
551

552
    if (_debugging) {
×
553
        LogDebug() << "Going to open writeonly: " << path;
×
554
    }
555

556
    // fail only if requested open for read
557
    std::error_code ec;
×
558
    if (!fs::exists(path, ec)) {
×
559
        LogWarn() << "FTP: Open failed - file not found";
×
560
        response.opcode = Opcode::RSP_NAK;
×
561
        response.size = 1;
×
562
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
563
        _send_mavlink_ftp_message(response);
×
564
        return;
×
565
    }
566

567
    auto file_size = static_cast<uint32_t>(fs::file_size(path, ec));
×
568
    if (ec) {
×
569
        LogErr() << "Could not determine file size of '" << path << "': " << ec.message();
×
570
        return;
×
571
    }
572

573
    if (_debugging) {
×
574
        LogDebug() << "Determined filesize to be: " << file_size << " bytes";
×
575
    }
576

577
    std::ofstream ofstream;
×
578
    ofstream.open(path, std::ios::out | std::ios::binary);
×
579

580
    if (!ofstream.is_open()) {
×
581
        LogWarn() << "FTP: Open failed";
×
582
        response.opcode = Opcode::RSP_NAK;
×
583
        response.size = 1;
×
584
        response.data[0] = ServerResult::ERR_FAIL;
×
585
        _send_mavlink_ftp_message(response);
×
586
        return;
×
587
    }
588

589
    _session_info.ofstream = std::move(ofstream);
×
590
    _session_info.file_size = file_size;
×
591

592
    response.opcode = Opcode::RSP_ACK;
×
593
    response.session = 0;
×
594
    response.size = sizeof(uint32_t);
×
595
    std::memcpy(response.data, &file_size, response.size);
×
596

597
    _send_mavlink_ftp_message(response);
×
598
}
×
599

600
void MavlinkFtpServer::_work_create_file(const PayloadHeader& payload)
7✔
601
{
602
    auto response = PayloadHeader{};
7✔
603
    response.seq_number = payload.seq_number + 1;
7✔
604
    response.req_opcode = payload.opcode;
7✔
605

606
    std::lock_guard<std::mutex> lock(_mutex);
7✔
607
    if (_session_info.ofstream.is_open()) {
7✔
608
        _reset();
1✔
609
    }
610

611
    std::string path;
7✔
612
    {
613
        std::lock_guard<std::mutex> tmp_lock(_tmp_files_mutex);
7✔
614
        const auto it = _tmp_files.find(_data_as_string(payload));
7✔
615
        if (it != _tmp_files.end()) {
7✔
616
            path = it->second;
×
617
        } else {
618
            auto maybe_path = _path_from_payload(payload);
7✔
619
            if (std::holds_alternative<ServerResult>(maybe_path)) {
7✔
620
                response.opcode = Opcode::RSP_NAK;
2✔
621
                response.size = 1;
2✔
622
                response.data[0] = std::get<ServerResult>(maybe_path);
2✔
623
                _send_mavlink_ftp_message(response);
2✔
624
                return;
2✔
625
            }
626

627
            path = std::get<std::string>(maybe_path);
5✔
628
        }
7✔
629
    }
7✔
630

631
    if (path.empty()) {
5✔
632
        response.opcode = Opcode::RSP_NAK;
×
633
        response.size = 1;
×
634
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
635
        _send_mavlink_ftp_message(response);
×
636
        return;
×
637
    }
638

639
    if (_debugging) {
5✔
640
        LogInfo() << "Finding " << path << " in " << _root_dir;
×
641
    }
642
    if (path.rfind(_root_dir, 0) != 0) {
5✔
643
        LogWarn() << "FTP: invalid path " << path;
×
644
        response.opcode = Opcode::RSP_NAK;
×
645
        response.size = 1;
×
646
        response.data[0] = ServerResult::ERR_FAIL;
×
647
        _send_mavlink_ftp_message(response);
×
648
        return;
×
649
    }
650

651
    if (_debugging) {
5✔
652
        LogDebug() << "Creating file: " << path;
×
653
    }
654

655
    std::ofstream ofstream;
5✔
656
    ofstream.open(path, std::ios::out | std::ios::binary);
5✔
657

658
    if (!ofstream.is_open()) {
5✔
659
        LogWarn() << "FTP: Open failed";
×
660
        response.opcode = Opcode::RSP_NAK;
×
661
        response.size = 1;
×
662
        response.data[0] = ServerResult::ERR_FAIL;
×
663
        _send_mavlink_ftp_message(response);
×
664
        return;
×
665
    }
666

667
    _session_info.ofstream = std::move(ofstream);
5✔
668
    _session_info.file_size = 0;
5✔
669

670
    response.session = 0;
5✔
671
    response.size = 0;
5✔
672
    response.opcode = Opcode::RSP_ACK;
5✔
673

674
    _send_mavlink_ftp_message(response);
5✔
675
}
9✔
676

677
void MavlinkFtpServer::_work_read(const PayloadHeader& payload)
272✔
678
{
679
    auto response = PayloadHeader{};
272✔
680
    response.seq_number = payload.seq_number + 1;
272✔
681
    response.req_opcode = payload.opcode;
272✔
682

683
    std::lock_guard<std::mutex> lock(_mutex);
272✔
684
    if (payload.session != 0 || !_session_info.ifstream.is_open()) {
272✔
685
        _reset();
×
686
    }
687

688
    // We have to test seek past EOF ourselves, lseek will allow seek past EOF
689
    if (payload.offset >= _session_info.file_size) {
272✔
690
        response.opcode = Opcode::RSP_NAK;
×
691
        response.size = 1;
×
692
        response.data[0] = ServerResult::ERR_EOF;
×
693
        if (_debugging) {
×
694
            LogDebug() << "Reached EOF reading";
×
695
        }
696
        _send_mavlink_ftp_message(response);
×
697
        return;
×
698
    }
699

700
    _session_info.ifstream.seekg(payload.offset);
272✔
701
    if (_session_info.ifstream.fail()) {
272✔
702
        response.opcode = Opcode::RSP_NAK;
×
703
        response.size = 1;
×
704
        response.data[0] = ServerResult::ERR_FAIL;
×
705
        LogWarn() << "Seek failed";
×
706
        _send_mavlink_ftp_message(response);
×
707
        return;
×
708
    }
709

710
    if (_debugging) {
272✔
711
        LogWarn() << "Read at " << payload.offset << " for " << int(payload.size);
×
712
    }
713

714
    _session_info.ifstream.read(reinterpret_cast<char*>(response.data), payload.size);
272✔
715

716
    if (_session_info.ifstream.fail()) {
272✔
717
        response.opcode = Opcode::RSP_NAK;
×
718
        response.size = 1;
×
719
        response.data[0] = ServerResult::ERR_FAIL;
×
720
        LogWarn() << "Read failed";
×
721
        _send_mavlink_ftp_message(response);
×
722
        return;
×
723
    }
724

725
    const uint32_t bytes_read = _session_info.ifstream.gcount();
272✔
726

727
    response.offset = payload.offset;
272✔
728
    response.size = bytes_read;
272✔
729
    response.opcode = Opcode::RSP_ACK;
272✔
730

731
    _send_mavlink_ftp_message(response);
272✔
732
}
272✔
733

734
void MavlinkFtpServer::_work_burst(const PayloadHeader& payload)
8✔
735
{
736
    auto response = PayloadHeader{};
8✔
737
    response.req_opcode = payload.opcode;
8✔
738

739
    std::lock_guard<std::mutex> lock(_mutex);
8✔
740
    if (payload.session != 0 || !_session_info.ifstream.is_open()) {
8✔
741
        _reset();
×
742
    }
743

744
    // We have to test seek past EOF ourselves, lseek will allow seek past EOF
745
    if (payload.offset >= _session_info.file_size) {
8✔
746
        response.seq_number = payload.seq_number + 1;
×
747
        response.opcode = Opcode::RSP_NAK;
×
748
        response.size = 1;
×
749
        response.data[0] = ServerResult::ERR_EOF;
×
750
        if (_debugging) {
×
751
            LogDebug() << "Reached EOF reading";
×
752
        }
753
        _send_mavlink_ftp_message(response);
×
754
        return;
×
755
    }
756

757
    if (_debugging) {
8✔
758
        LogDebug() << "Seek to " << payload.offset;
×
759
    }
760
    _session_info.ifstream.seekg(payload.offset);
8✔
761
    if (_session_info.ifstream.fail()) {
8✔
762
        response.seq_number = payload.seq_number + 1;
×
763
        response.opcode = Opcode::RSP_NAK;
×
764
        response.size = 1;
×
765
        response.data[0] = ServerResult::ERR_FAIL;
×
766
        LogErr() << "Seek failed";
×
767
        _send_mavlink_ftp_message(response);
×
768
        return;
×
769
    }
770

771
    _session_info.burst_offset = payload.offset;
8✔
772
    _session_info.burst_chunk_size = payload.size;
8✔
773
    _burst_seq = payload.seq_number + 1;
8✔
774

775
    if (_session_info.burst_thread.joinable()) {
8✔
776
        _session_info.burst_stop = true;
×
777
        _session_info.burst_thread.join();
×
778
    }
779

780
    _session_info.burst_stop = false;
8✔
781

782
    // Schedule sending out burst messages.
783
    _session_info.burst_thread = std::thread([this]() {
16✔
784
        while (!_session_info.burst_stop)
282✔
785
            if (_send_burst_packet())
282✔
786
                break;
8✔
787
    });
8✔
788

789
    // Don't send response as that's done in the call every burst call above.
790
}
8✔
791

792
// Returns true if sending is complete
793
bool MavlinkFtpServer::_send_burst_packet()
282✔
794
{
795
    std::lock_guard<std::mutex> lock(_mutex);
282✔
796
    if (!_session_info.ifstream.is_open()) {
282✔
797
        return false;
×
798
    }
799

800
    PayloadHeader burst_packet{};
282✔
801
    burst_packet.req_opcode = Opcode::CMD_BURST_READ_FILE;
282✔
802
    burst_packet.seq_number = _burst_seq++;
282✔
803

804
    _make_burst_packet(burst_packet);
282✔
805

806
    _send_mavlink_ftp_message(burst_packet);
282✔
807

808
    if (burst_packet.burst_complete == 1) {
282✔
809
        return true;
8✔
810
    }
811

812
    return false;
274✔
813
}
282✔
814

815
void MavlinkFtpServer::_make_burst_packet(PayloadHeader& packet)
282✔
816
{
817
    uint32_t bytes_to_read = std::min(
282✔
818
        static_cast<uint32_t>(_session_info.burst_chunk_size),
282✔
819
        _session_info.file_size - _session_info.burst_offset);
564✔
820

821
    if (_debugging) {
282✔
822
        LogDebug() << "Burst read of " << bytes_to_read << " bytes";
×
823
    }
824
    _session_info.ifstream.read(reinterpret_cast<char*>(packet.data), bytes_to_read);
282✔
825

826
    if (_session_info.ifstream.fail()) {
282✔
827
        packet.opcode = Opcode::RSP_NAK;
×
828
        packet.size = 1;
×
829
        packet.data[0] = ServerResult::ERR_FAIL;
×
830
        LogWarn() << "Burst read failed";
×
831
        return;
×
832
    }
833

834
    const uint32_t bytes_read = _session_info.ifstream.gcount();
282✔
835
    packet.size = bytes_read;
282✔
836
    packet.opcode = Opcode::RSP_ACK;
282✔
837

838
    packet.offset = _session_info.burst_offset;
282✔
839
    _session_info.burst_offset += bytes_read;
282✔
840

841
    if (_session_info.burst_offset == _session_info.file_size) {
282✔
842
        // Last read, we are done for this burst.
843
        packet.burst_complete = 1;
8✔
844
        if (_debugging) {
8✔
845
            LogDebug() << "Burst complete";
×
846
        }
847
    }
848
}
849

850
void MavlinkFtpServer::_work_write(const PayloadHeader& payload)
95✔
851
{
852
    auto response = PayloadHeader{};
95✔
853
    response.seq_number = payload.seq_number + 1;
95✔
854
    response.req_opcode = payload.opcode;
95✔
855

856
    std::lock_guard<std::mutex> lock(_mutex);
95✔
857
    if (payload.session != 0 && !_session_info.ofstream.is_open()) {
95✔
858
        _reset();
×
859
    }
860

861
    _session_info.ofstream.seekp(payload.offset);
95✔
862
    if (_session_info.ifstream.fail()) {
95✔
863
        response.opcode = Opcode::RSP_NAK;
×
864
        response.size = 1;
×
865
        response.data[0] = ServerResult::ERR_FAIL;
×
866
        LogWarn() << "Seek failed";
×
867
        _send_mavlink_ftp_message(response);
×
868
        return;
×
869
    }
870

871
    _session_info.ofstream.write(reinterpret_cast<const char*>(payload.data), payload.size);
95✔
872
    if (_session_info.ofstream.fail()) {
95✔
873
        response.opcode = Opcode::RSP_NAK;
×
874
        response.size = 1;
×
875
        response.data[0] = ServerResult::ERR_FAIL;
×
876
        LogWarn() << "Write failed";
×
877
        _send_mavlink_ftp_message(response);
×
878
        return;
×
879
    }
880

881
    response.opcode = Opcode::RSP_ACK;
95✔
882
    response.size = 0;
95✔
883

884
    _send_mavlink_ftp_message(response);
95✔
885
}
95✔
886

887
void MavlinkFtpServer::_work_terminate(const PayloadHeader& payload)
31✔
888
{
889
    {
890
        std::lock_guard<std::mutex> lock(_mutex);
31✔
891
        _reset();
31✔
892
    }
31✔
893

894
    auto response = PayloadHeader{};
31✔
895
    response.seq_number = payload.seq_number + 1;
31✔
896
    response.req_opcode = payload.opcode;
31✔
897
    response.opcode = Opcode::RSP_ACK;
31✔
898
    response.size = 0;
31✔
899
    _send_mavlink_ftp_message(response);
31✔
900
}
31✔
901

902
void MavlinkFtpServer::_reset()
106✔
903
{
904
    // requires lock
905
    if (_session_info.ifstream.is_open()) {
106✔
906
        _session_info.ifstream.close();
13✔
907
    }
908

909
    if (_session_info.ofstream.is_open()) {
106✔
910
        _session_info.ofstream.close();
5✔
911
    }
912

913
    _session_info.burst_stop = true;
106✔
914
    if (_session_info.burst_thread.joinable()) {
106✔
915
        _session_info.burst_thread.join();
8✔
916
    }
917
}
106✔
918

919
void MavlinkFtpServer::_work_reset(const PayloadHeader& payload)
×
920
{
921
    {
922
        std::lock_guard<std::mutex> lock(_mutex);
×
923
        _reset();
×
924
    }
×
925

926
    auto response = PayloadHeader{};
×
927
    response.seq_number = payload.seq_number + 1;
×
928
    response.req_opcode = payload.opcode;
×
929
    response.opcode = Opcode::RSP_ACK;
×
930
    response.size = 0;
×
931
    _send_mavlink_ftp_message(response);
×
932
}
×
933

934
void MavlinkFtpServer::_work_remove_directory(const PayloadHeader& payload)
2✔
935
{
936
    auto response = PayloadHeader{};
2✔
937
    response.seq_number = payload.seq_number + 1;
2✔
938
    response.req_opcode = payload.opcode;
2✔
939

940
    std::lock_guard<std::mutex> lock(_mutex);
2✔
941

942
    auto maybe_path = _path_from_payload(payload);
2✔
943
    if (std::holds_alternative<ServerResult>(maybe_path)) {
2✔
944
        response.opcode = Opcode::RSP_NAK;
×
945
        response.size = 1;
×
946
        response.data[0] = std::get<ServerResult>(maybe_path);
×
947
        _send_mavlink_ftp_message(response);
×
948
        return;
×
949
    }
950

951
    fs::path path = std::get<std::string>(maybe_path);
2✔
952

953
    std::error_code ec;
2✔
954
    if (!fs::exists(path, ec)) {
2✔
955
        response.opcode = Opcode::RSP_NAK;
×
956
        response.size = 1;
×
957
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
958
        _send_mavlink_ftp_message(response);
×
959
        return;
×
960
    }
961
    if (fs::remove(path, ec)) {
2✔
962
        response.opcode = Opcode::RSP_ACK;
1✔
963
        response.size = 0;
1✔
964
    } else {
965
        response.opcode = Opcode::RSP_NAK;
1✔
966
        response.size = 1;
1✔
967
        response.data[0] = ServerResult::ERR_FAIL;
1✔
968
    }
969

970
    _send_mavlink_ftp_message(response);
2✔
971
}
2✔
972

973
void MavlinkFtpServer::_work_create_directory(const PayloadHeader& payload)
3✔
974
{
975
    auto response = PayloadHeader{};
3✔
976
    response.seq_number = payload.seq_number + 1;
3✔
977
    response.req_opcode = payload.opcode;
3✔
978

979
    std::lock_guard<std::mutex> lock(_mutex);
3✔
980

981
    auto maybe_path = _path_from_payload(payload);
3✔
982
    if (std::holds_alternative<ServerResult>(maybe_path)) {
3✔
983
        response.opcode = Opcode::RSP_NAK;
2✔
984
        response.size = 1;
2✔
985
        response.data[0] = std::get<ServerResult>(maybe_path);
2✔
986
        _send_mavlink_ftp_message(response);
2✔
987
        return;
2✔
988
    }
989

990
    auto path = std::get<std::string>(maybe_path);
1✔
991

992
    std::error_code ec;
1✔
993
    if (fs::exists(path, ec)) {
1✔
994
        response.opcode = Opcode::RSP_NAK;
×
995
        response.size = 1;
×
996
        response.data[0] = ServerResult::ERR_FAIL_FILE_EXISTS;
×
997
        _send_mavlink_ftp_message(response);
×
998
        return;
×
999
    }
1000

1001
    if (fs::create_directory(path, ec)) {
1✔
1002
        response.opcode = Opcode::RSP_ACK;
1✔
1003
    } else {
1004
        response.opcode = Opcode::RSP_NAK;
×
1005
        response.size = 2;
×
1006
        response.data[0] = ServerResult::ERR_FAIL_ERRNO;
×
1007
        response.data[1] = static_cast<uint8_t>(ec.value());
×
1008
    }
1009

1010
    _send_mavlink_ftp_message(response);
1✔
1011
}
5✔
1012

1013
void MavlinkFtpServer::_work_remove_file(const PayloadHeader& payload)
4✔
1014
{
1015
    auto response = PayloadHeader{};
4✔
1016
    response.seq_number = payload.seq_number + 1;
4✔
1017
    response.req_opcode = payload.opcode;
4✔
1018

1019
    std::lock_guard<std::mutex> lock(_mutex);
4✔
1020

1021
    auto maybe_path = _path_from_payload(payload);
4✔
1022
    if (std::holds_alternative<ServerResult>(maybe_path)) {
4✔
1023
        response.opcode = Opcode::RSP_NAK;
2✔
1024
        response.size = 1;
2✔
1025
        response.data[0] = std::get<ServerResult>(maybe_path);
2✔
1026
        _send_mavlink_ftp_message(response);
2✔
1027
        return;
2✔
1028
    }
1029

1030
    auto path = std::get<std::string>(maybe_path);
2✔
1031

1032
    std::error_code ec;
2✔
1033
    if (!fs::exists(path, ec)) {
2✔
1034
        response.opcode = Opcode::RSP_NAK;
1✔
1035
        response.size = 1;
1✔
1036
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
1✔
1037
        _send_mavlink_ftp_message(response);
1✔
1038
        return;
1✔
1039
    }
1040
    if (fs::remove(path, ec)) {
1✔
1041
        response.opcode = Opcode::RSP_ACK;
1✔
1042
    } else {
1043
        response.opcode = Opcode::RSP_NAK;
×
1044
        response.size = 1;
×
1045
        response.data[0] = ServerResult::ERR_FAIL;
×
1046
    }
1047

1048
    _send_mavlink_ftp_message(response);
1✔
1049
}
8✔
1050

1051
void MavlinkFtpServer::_work_rename(const PayloadHeader& payload)
2✔
1052
{
1053
    auto response = PayloadHeader{};
2✔
1054
    response.seq_number = payload.seq_number + 1;
2✔
1055
    response.req_opcode = payload.opcode;
2✔
1056

1057
    std::lock_guard<std::mutex> lock(_mutex);
2✔
1058

1059
    auto maybe_old_name = _path_from_payload(payload, 0);
2✔
1060

1061
    if (std::holds_alternative<ServerResult>(maybe_old_name)) {
2✔
1062
        response.opcode = Opcode::RSP_NAK;
1✔
1063
        response.size = 1;
1✔
1064
        response.data[0] = std::get<ServerResult>(maybe_old_name);
1✔
1065
        _send_mavlink_ftp_message(response);
1✔
1066
        return;
1✔
1067
    }
1068

1069
    auto old_name = std::get<std::string>(maybe_old_name);
1✔
1070

1071
    auto maybe_new_name = _path_from_payload(payload, 1);
1✔
1072

1073
    if (std::holds_alternative<ServerResult>(maybe_new_name)) {
1✔
1074
        response.opcode = Opcode::RSP_NAK;
×
1075
        response.size = 1;
×
1076
        response.data[0] = std::get<ServerResult>(maybe_new_name);
×
1077
        _send_mavlink_ftp_message(response);
×
1078
        return;
×
1079
    }
1080

1081
    auto new_name = std::get<std::string>(maybe_new_name);
1✔
1082

1083
    if (_debugging) {
1✔
1084
        LogDebug() << "Rename from old_name " << old_name << " to " << new_name;
×
1085
    }
1086

1087
    std::error_code ec;
1✔
1088
    if (!fs::exists(old_name, ec)) {
1✔
1089
        response.opcode = Opcode::RSP_NAK;
×
1090
        response.size = 1;
×
1091
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
1092
        _send_mavlink_ftp_message(response);
×
1093
        return;
×
1094
    }
1095

1096
    fs::rename(old_name, new_name, ec);
1✔
1097
    if (!ec) {
1✔
1098
        response.opcode = Opcode::RSP_ACK;
1✔
1099
    } else {
1100
        response.opcode = Opcode::RSP_NAK;
×
1101
        response.size = 1;
×
1102
        response.data[0] = ServerResult::ERR_FAIL;
×
1103
    }
1104

1105
    _send_mavlink_ftp_message(response);
1✔
1106
}
3✔
1107

1108
MavlinkFtpServer::ServerResult
1109
MavlinkFtpServer::_calc_local_file_crc32(const std::string& path, uint32_t& csum)
2✔
1110
{
1111
    std::error_code ec;
2✔
1112
    if (!fs::exists(path, ec)) {
2✔
1113
        return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
1114
    }
1115

1116
    std::ifstream ifstream;
2✔
1117
    ifstream.open(path, std::ios::in | std::ios::binary);
2✔
1118

1119
    if (!ifstream.is_open()) {
2✔
1120
        return ServerResult::ERR_FILE_IO_ERROR;
×
1121
    }
1122

1123
    // Read whole file in buffer size chunks
1124
    Crc32 checksum;
2✔
1125
    char buffer[18392];
2✔
1126
    do {
1127
        ifstream.read(buffer, sizeof(buffer));
2✔
1128

1129
        if (ifstream.fail() && !ifstream.eof()) {
2✔
1130
            ifstream.close();
×
1131
            return ServerResult::ERR_FILE_IO_ERROR;
×
1132
        }
1133

1134
        auto bytes_read = ifstream.gcount();
2✔
1135
        checksum.add((uint8_t*)buffer, bytes_read);
2✔
1136

1137
    } while (!ifstream.eof());
2✔
1138

1139
    ifstream.close();
2✔
1140

1141
    csum = checksum.get();
2✔
1142

1143
    return ServerResult::SUCCESS;
2✔
1144
}
2✔
1145

1146
void MavlinkFtpServer::_work_calc_file_CRC32(const PayloadHeader& payload)
3✔
1147
{
1148
    auto response = PayloadHeader{};
3✔
1149
    response.seq_number = payload.seq_number + 1;
3✔
1150
    response.req_opcode = payload.opcode;
3✔
1151

1152
    std::lock_guard<std::mutex> lock(_mutex);
3✔
1153

1154
    auto maybe_path = _path_from_payload(payload);
3✔
1155
    if (std::holds_alternative<ServerResult>(maybe_path)) {
3✔
1156
        response.opcode = Opcode::RSP_NAK;
1✔
1157
        response.size = 1;
1✔
1158
        response.data[0] = std::get<ServerResult>(maybe_path);
1✔
1159
        _send_mavlink_ftp_message(response);
1✔
1160
        return;
1✔
1161
    }
1162

1163
    auto path = std::get<std::string>(maybe_path);
2✔
1164

1165
    std::error_code ec;
2✔
1166
    if (!fs::exists(path, ec)) {
2✔
1167
        response.opcode = Opcode::RSP_NAK;
×
1168
        response.size = 1;
×
1169
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
1170
        _send_mavlink_ftp_message(response);
×
1171
        return;
×
1172
    }
1173

1174
    uint32_t checksum;
2✔
1175
    ServerResult res = _calc_local_file_crc32(path, checksum);
2✔
1176
    if (res != ServerResult::SUCCESS) {
2✔
1177
        response.opcode = Opcode::RSP_NAK;
×
1178
        response.size = 1;
×
1179
        response.data[0] = res;
×
1180
        _send_mavlink_ftp_message(response);
×
1181
        return;
×
1182
    }
1183

1184
    response.opcode = Opcode::RSP_ACK;
2✔
1185
    response.size = sizeof(uint32_t);
2✔
1186
    std::memcpy(response.data, &checksum, response.size);
2✔
1187

1188
    _send_mavlink_ftp_message(response);
2✔
1189
}
4✔
1190

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