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

mavlink / MAVSDK / 16636200771

30 Jul 2025 11:46PM UTC coverage: 44.271% (-2.0%) from 46.31%
16636200771

Pull #2626

github

web-flow
Merge bfd339d18 into c0a7c02a0
Pull Request #2626: core: flush after each Log* line

237 of 350 new or added lines in 32 files covered. (67.71%)

405 existing lines in 18 files now uncovered.

15319 of 34603 relevant lines covered (44.27%)

293.66 hits per line

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

60.17
/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) :
88✔
16
    _server_component_impl(server_component_impl)
88✔
17
{
18
    if (const char* env_p = std::getenv("MAVSDK_FTP_DEBUGGING")) {
88✔
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(
88✔
26
        MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL,
27
        [this](const mavlink_message_t& message) { process_mavlink_ftp_message(message); },
1,245✔
28
        this);
29
}
88✔
30

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

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

40
    if (_debugging) {
1,245✔
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,490✔
47
        ftp_req.target_system != _server_component_impl.get_own_system_id()) {
1,245✔
48
        if (_debugging) {
×
49
            LogDebug() << "Received FTP message with wrong target system ID";
×
50
        }
51
        return;
×
52
    }
53

54
    if (ftp_req.target_component != 0 &&
2,472✔
55
        ftp_req.target_component != _server_component_impl.get_own_component_id()) {
1,227✔
56
        if (_debugging) {
9✔
57
            LogDebug() << "Received FTP message with wrong target component ID";
×
58
        }
59
        return;
9✔
60
    }
61

62
    const PayloadHeader& payload = *reinterpret_cast<PayloadHeader*>(&ftp_req.payload[0]);
1,236✔
63

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

74
    } else {
75
        if (_debugging) {
1,236✔
76
            LogDebug() << "FTP opcode: " << (int)payload.opcode << ", size: " << (int)payload.size
×
77
                       << ", offset: " << (int)payload.offset << ", seq: " << payload.seq_number;
×
78
        }
79

80
        _target_system_id = msg.sysid;
1,236✔
81
        _target_component_id = msg.compid;
1,236✔
82

83
        switch (payload.opcode) {
1,236✔
84
            case Opcode::CMD_NONE:
×
85
                if (_debugging) {
×
86
                    LogDebug() << "OPC:CMD_NONE";
×
87
                }
88
                break;
×
89

90
            case Opcode::CMD_TERMINATE_SESSION:
29✔
91
                if (_debugging) {
29✔
92
                    LogDebug() << "OPC:CMD_TERMINATE_SESSION";
×
93
                }
94
                _work_terminate(payload);
29✔
95
                break;
29✔
96

97
            case Opcode::CMD_RESET_SESSIONS:
×
98
                if (_debugging) {
×
99
                    LogDebug() << "OPC:CMD_RESET_SESSIONS";
×
100
                }
101
                _work_reset(payload);
×
102
                break;
×
103

104
            case Opcode::CMD_LIST_DIRECTORY:
11✔
105
                if (_debugging) {
11✔
106
                    LogDebug() << "OPC:CMD_LIST_DIRECTORY";
×
107
                }
108
                _work_list(payload);
11✔
109
                break;
11✔
110

111
            case Opcode::CMD_OPEN_FILE_RO:
18✔
112
                if (_debugging) {
18✔
113
                    LogDebug() << "OPC:CMD_OPEN_FILE_RO";
×
114
                }
115
                _work_open_file_readonly(payload);
18✔
116
                break;
18✔
117

118
            case Opcode::CMD_CREATE_FILE:
7✔
119
                if (_debugging) {
7✔
120
                    LogDebug() << "OPC:CMD_CREATE_FILE";
×
121
                }
122
                _work_create_file(payload);
7✔
123
                break;
7✔
124

125
            case Opcode::CMD_OPEN_FILE_WO:
×
126
                if (_debugging) {
×
127
                    LogDebug() << "OPC:CMD_OPEN_FILE_WO";
×
128
                }
129
                _work_open_file_writeonly(payload);
×
130
                break;
×
131

132
            case Opcode::CMD_READ_FILE:
304✔
133
                if (_debugging) {
304✔
134
                    LogDebug() << "OPC:CMD_READ_FILE";
×
135
                }
136
                _work_read(payload);
304✔
137
                break;
304✔
138

139
            case Opcode::CMD_BURST_READ_FILE:
8✔
140
                if (_debugging) {
8✔
141
                    LogDebug() << "OPC:CMD_BURST_READ_FILE";
×
142
                }
143
                _work_burst(payload);
8✔
144
                break;
8✔
145

146
            case Opcode::CMD_WRITE_FILE:
98✔
147
                if (_debugging) {
98✔
148
                    LogDebug() << "OPC:CMD_WRITE_FILE";
×
149
                }
150
                _work_write(payload);
98✔
151
                break;
98✔
152

153
            case Opcode::CMD_REMOVE_FILE:
4✔
154
                if (_debugging) {
4✔
155
                    LogDebug() << "OPC:CMD_REMOVE_FILE";
×
156
                }
157
                _work_remove_file(payload);
4✔
158
                break;
4✔
159

160
            case Opcode::CMD_RENAME:
2✔
161
                if (_debugging) {
2✔
162
                    LogDebug() << "OPC:CMD_RENAME";
×
163
                }
164
                _work_rename(payload);
2✔
165
                break;
2✔
166

167
            case Opcode::CMD_CREATE_DIRECTORY:
3✔
168
                if (_debugging) {
3✔
169
                    LogDebug() << "OPC:CMD_CREATE_DIRECTORY";
×
170
                }
171
                _work_create_directory(payload);
3✔
172
                break;
3✔
173

174
            case Opcode::CMD_REMOVE_DIRECTORY:
2✔
175
                if (_debugging) {
2✔
176
                    LogDebug() << "OPC:CMD_REMOVE_DIRECTORY";
×
177
                }
178
                _work_remove_directory(payload);
2✔
179
                break;
2✔
180

181
            case Opcode::CMD_CALC_FILE_CRC32:
3✔
182
                if (_debugging) {
3✔
183
                    LogDebug() << "OPC:CMD_CALC_FILE_CRC32";
×
184
                }
185
                _work_calc_file_CRC32(payload);
3✔
186
                break;
3✔
187

188
            default:
747✔
189
                // Not for us, ignore it.
190
                return;
747✔
191
        }
192
    }
193
}
194

195
MavlinkFtpServer::~MavlinkFtpServer()
88✔
196
{
197
    _server_component_impl.unregister_all_mavlink_message_handlers(this);
88✔
198

199
    std::lock_guard<std::mutex> lock(_mutex);
88✔
200
    _reset();
88✔
201
}
176✔
202

203
void MavlinkFtpServer::_send_mavlink_ftp_message(const PayloadHeader& payload)
763✔
204
{
205
    if (uint8_t(payload.opcode) == 0) {
763✔
206
        abort();
×
207
    }
208

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

224
std::string MavlinkFtpServer::_data_as_string(const PayloadHeader& payload, size_t entry)
76✔
225
{
226
    size_t start = 0;
76✔
227
    size_t end = 0;
76✔
228
    std::string result;
76✔
229

230
    for (int i = entry; i >= 0; --i) {
153✔
231
        start = end;
77✔
232

233
        // Defensive check: prevent buffer overflow when start >= max_data_length
234
        if (start >= max_data_length) {
77✔
NEW
235
            LogErr() << "ABORT: FTP _data_as_string buffer overflow - start=" << start
×
NEW
236
                     << " >= max_data_length=" << max_data_length;
×
NEW
237
            abort();
×
238
        }
239

240
        end +=
77✔
241
            strnlen(reinterpret_cast<const char*>(&payload.data[start]), max_data_length - start) +
77✔
242
            1;
243

244
        // Additional defensive check: prevent end from exceeding buffer
245
        if (end > max_data_length) {
77✔
NEW
246
            LogErr() << "ABORT: FTP _data_as_string end overflow - end=" << end
×
NEW
247
                     << " > max_data_length=" << max_data_length;
×
NEW
248
            abort();
×
249
        }
250
    }
251

252
    // Defensive check: prevent memcpy overflow
253
    if (end < start || (end - start) > max_data_length) {
76✔
NEW
254
        LogErr() << "ABORT: FTP _data_as_string memcpy bounds - start=" << start << " end=" << end
×
NEW
255
                 << " max_data_length=" << max_data_length;
×
NEW
256
        abort();
×
257
    }
258

259
    result.resize(end - start);
76✔
260
    std::memcpy(result.data(), &payload.data[start], end - start);
76✔
261

262
    return result;
76✔
263
}
264

265
std::variant<std::string, MavlinkFtpServer::ServerResult>
266
MavlinkFtpServer::_path_from_payload(const PayloadHeader& payload, size_t entry)
51✔
267
{
268
    // Requires lock
269

270
    auto data = _data_as_string(payload, entry);
51✔
271
    return _path_from_string(data);
51✔
272
}
51✔
273

274
std::variant<std::string, MavlinkFtpServer::ServerResult>
275
MavlinkFtpServer::_path_from_string(const std::string& payload_path)
51✔
276
{
277
    // Requires lock
278

279
    // No permission whatsoever if the root dir is not set.
280
    if (_root_dir.empty()) {
51✔
281
        LogWarn() << "Root dir not set!";
9✔
282
        return ServerResult::ERR_FAIL;
9✔
283
    }
284

285
    // Take a copy before we mess with it.
286
    auto temp_path = payload_path;
42✔
287

288
    // We strip leading slashes (like absolute paths).
289
    if (temp_path.size() >= 1 && temp_path[0] == '/') {
42✔
290
        temp_path = temp_path.substr(1, temp_path.size());
×
291
    }
292

293
    fs::path combined_path = (fs::path(_root_dir) / temp_path).lexically_normal();
168✔
294

295
    // Check whether the combined path is inside the root dir.
296
    // From: https://stackoverflow.com/a/61125335/8548472
297
    auto ret = std::mismatch(_root_dir.begin(), _root_dir.end(), combined_path.string().begin());
42✔
298
    if (ret.first != _root_dir.end()) {
42✔
299
        LogWarn() << "Not inside root dir: " << combined_path.string()
12✔
300
                  << ", root dir: " << _root_dir;
12✔
301
        return ServerResult::ERR_FAIL;
4✔
302
    }
303

304
    return combined_path.string();
38✔
305
}
42✔
306

307
void MavlinkFtpServer::set_root_directory(const std::string& root_dir)
27✔
308
{
309
    std::lock_guard<std::mutex> lock(_mutex);
27✔
310

311
    std::error_code ec;
27✔
312
    _root_dir = fs::canonical(fs::path(root_dir), ec).string();
27✔
313
    if (ec) {
27✔
314
        LogWarn() << "Root dir could not be made absolute: " << ec.message();
×
315
    }
316
    if (_debugging) {
27✔
317
        LogDebug() << "Set root dir to: " << _root_dir << " from: " << root_dir;
×
318
    }
319
}
27✔
320

321
void MavlinkFtpServer::_work_list(const PayloadHeader& payload)
11✔
322
{
323
    auto response = PayloadHeader{};
11✔
324
    response.seq_number = payload.seq_number + 1;
11✔
325
    response.req_opcode = payload.opcode;
11✔
326

327
    std::lock_guard<std::mutex> lock(_mutex);
11✔
328

329
    auto maybe_path = _path_from_payload(payload);
11✔
330
    if (std::holds_alternative<ServerResult>(maybe_path)) {
11✔
331
        response.opcode = Opcode::RSP_NAK;
1✔
332
        response.size = 1;
1✔
333
        response.data[0] = std::get<ServerResult>(maybe_path);
1✔
334
        _send_mavlink_ftp_message(response);
1✔
335
        return;
1✔
336
    }
337

338
    fs::path path = std::get<std::string>(maybe_path);
10✔
339

340
    uint8_t offset = 0;
10✔
341

342
    // Move to the requested offset
343
    uint32_t requested_offset = payload.offset;
10✔
344

345
    std::error_code ec;
10✔
346
    if (!fs::exists(path, ec)) {
10✔
347
        LogWarn() << "FTP: can't open path " << path;
×
348
        // this is not an FTP error, abort directory by simulating eof
349
        response.opcode = Opcode::RSP_NAK;
×
350
        response.size = 1;
×
351
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
352
        _send_mavlink_ftp_message(response);
×
353
        return;
×
354
    }
355

356
    if (_debugging) {
10✔
357
        LogDebug() << "Opening path: " << path.string();
×
358
    }
359

360
    for (const auto& entry : fs::directory_iterator(fs::canonical(path))) {
1,241✔
361
        if (requested_offset > 0) {
1,219✔
362
            requested_offset--;
1,011✔
363
            continue;
1,011✔
364
        }
365
        const auto name = entry.path().filename();
208✔
366

367
        std::string payload_str;
208✔
368

369
        const auto is_regular_file = entry.is_regular_file(ec);
208✔
370
        if (ec) {
208✔
371
            LogWarn() << "Could not determine whether '" << entry.path().string()
×
372
                      << "' is a file: " << ec.message();
×
373
            continue;
×
374
        }
375

376
        const auto is_directory = entry.is_directory(ec);
208✔
377
        if (ec) {
208✔
378
            LogWarn() << "Could not determine whether '" << entry.path().string()
×
379
                      << "' is a directory: " << ec.message();
×
380
            continue;
×
381
        }
382

383
        if (is_regular_file) {
208✔
384
            const auto filesize = fs::file_size(entry.path(), ec);
106✔
385
            if (ec) {
106✔
386
                LogWarn() << "Could not get file size of '" << entry.path().string()
×
387
                          << "': " << ec.message();
×
388
                continue;
×
389
            }
390

391
            if (_debugging) {
106✔
392
                LogDebug() << "Found file: " << name.string() << ", size: " << filesize << " bytes";
×
393
            }
394

395
            payload_str += 'F';
106✔
396
            payload_str += name.string();
106✔
397
            payload_str += '\t';
106✔
398
            payload_str += std::to_string(filesize);
106✔
399

400
        } else if (is_directory) {
102✔
401
            if (_debugging) {
102✔
402
                LogDebug() << "Found directory: " << name.string();
×
403
            }
404

405
            payload_str += 'D';
102✔
406
            payload_str += name.string();
102✔
407

408
        } else {
409
            // Ignore all other types.
410
            continue;
×
411
        }
412

413
        auto required_len = payload_str.length() + 1;
208✔
414

415
        // Do we have room for the dir entry and the null terminator?
416
        if (offset + required_len > max_data_length) {
208✔
417
            break;
8✔
418
        }
419

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

422
        offset += static_cast<uint8_t>(required_len);
200✔
423
    }
226✔
424

425
    if (offset == 0) {
10✔
426
        // We are done and need to respond with EOF.
427
        response.opcode = Opcode::RSP_NAK;
1✔
428
        response.size = 1;
1✔
429
        response.data[0] = ServerResult::ERR_EOF;
1✔
430

431
    } else {
432
        response.opcode = Opcode::RSP_ACK;
9✔
433
        response.size = offset;
9✔
434
    }
435

436
    _send_mavlink_ftp_message(response);
10✔
437
}
12✔
438

439
void MavlinkFtpServer::_work_open_file_readonly(const PayloadHeader& payload)
18✔
440
{
441
    auto response = PayloadHeader{};
18✔
442
    response.seq_number = payload.seq_number + 1;
18✔
443
    response.req_opcode = payload.opcode;
18✔
444

445
    std::lock_guard<std::mutex> lock(_mutex);
18✔
446
    if (_session_info.ifstream.is_open()) {
18✔
447
        _reset();
2✔
448
    }
449

450
    std::string path;
18✔
451
    {
452
        std::lock_guard<std::mutex> tmp_lock(_tmp_files_mutex);
18✔
453
        const auto it = _tmp_files.find(_data_as_string(payload));
18✔
454
        if (it != _tmp_files.end()) {
18✔
455
            path = it->second;
×
456
        } else {
457
            auto maybe_path = _path_from_payload(payload);
18✔
458
            if (std::holds_alternative<ServerResult>(maybe_path)) {
18✔
459
                response.opcode = Opcode::RSP_NAK;
4✔
460
                response.size = 1;
4✔
461
                response.data[0] = std::get<ServerResult>(maybe_path);
4✔
462
                _send_mavlink_ftp_message(response);
4✔
463
                return;
4✔
464
            }
465

466
            path = std::get<std::string>(maybe_path);
14✔
467
        }
18✔
468
    }
18✔
469

470
    if (_debugging) {
14✔
471
        LogInfo() << "Finding " << path << " in " << _root_dir;
×
472
    }
473
    if (path.rfind(_root_dir, 0) != 0) {
14✔
474
        LogWarn() << "FTP: invalid path " << path;
×
475
        response.opcode = Opcode::RSP_NAK;
×
476
        response.size = 1;
×
477
        response.data[0] = ServerResult::ERR_FAIL;
×
478
        _send_mavlink_ftp_message(response);
×
479
        return;
×
480
    }
481

482
    if (_debugging) {
14✔
483
        LogDebug() << "Going to open readonly: " << path;
×
484
    }
485

486
    std::error_code ec;
14✔
487
    if (!fs::exists(path, ec)) {
14✔
488
        LogErr() << "FTP: Open failed - file doesn't exist";
×
489
        response.opcode = Opcode::RSP_NAK;
×
490
        response.size = 1;
×
491
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
492
        _send_mavlink_ftp_message(response);
×
493
        return;
×
494
    }
495

496
    auto file_size = static_cast<uint32_t>(fs::file_size(path, ec));
14✔
497
    if (ec) {
14✔
498
        LogErr() << "Could not determine file size of '" << path << "': " << ec.message();
×
499
        return;
×
500
    }
501

502
    if (_debugging) {
14✔
503
        LogDebug() << "Determined filesize to be: " << file_size << " bytes";
×
504
    }
505

506
    std::ifstream ifstream;
14✔
507
    ifstream.open(path, std::ios::in | std::ios::binary);
14✔
508

509
    if (!ifstream.is_open()) {
14✔
510
        LogWarn() << "FTP: Open failed";
×
511
        response.opcode = Opcode::RSP_NAK;
×
512
        response.size = 1;
×
513
        response.data[0] = ServerResult::ERR_FAIL;
×
514
        _send_mavlink_ftp_message(response);
×
515
        return;
×
516
    }
517

518
    _session_info.ifstream = std::move(ifstream);
14✔
519
    _session_info.file_size = file_size;
14✔
520

521
    response.opcode = Opcode::RSP_ACK;
14✔
522
    response.session = 0;
14✔
523
    response.seq_number = payload.seq_number + 1;
14✔
524
    response.size = sizeof(uint32_t);
14✔
525
    std::memcpy(response.data, &file_size, response.size);
14✔
526

527
    _send_mavlink_ftp_message(response);
14✔
528
}
22✔
529

530
void MavlinkFtpServer::_work_open_file_writeonly(const PayloadHeader& payload)
×
531
{
532
    auto response = PayloadHeader{};
×
533
    response.seq_number = payload.seq_number + 1;
×
534
    response.req_opcode = payload.opcode;
×
535

536
    std::lock_guard<std::mutex> lock(_mutex);
×
537

538
    if (_session_info.ofstream.is_open()) {
×
539
        _reset();
×
540
    }
541

542
    std::string path;
×
543
    {
544
        std::lock_guard<std::mutex> tmp_lock(_tmp_files_mutex);
×
545
        const auto it = _tmp_files.find(_data_as_string(payload));
×
546
        if (it != _tmp_files.end()) {
×
547
            path = it->second;
×
548
        } else {
549
            auto maybe_path = _path_from_payload(payload);
×
550
            if (std::holds_alternative<ServerResult>(maybe_path)) {
×
551
                response.opcode = Opcode::RSP_NAK;
×
552
                response.size = 1;
×
553
                response.data[0] = std::get<ServerResult>(maybe_path);
×
554
                _send_mavlink_ftp_message(response);
×
555
                return;
×
556
            }
557

558
            path = std::get<std::string>(maybe_path);
×
559
        }
×
560
    }
×
561

562
    if (path.empty()) {
×
563
        response.opcode = Opcode::RSP_NAK;
×
564
        response.size = 1;
×
565
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
566
        _send_mavlink_ftp_message(response);
×
567
        return;
×
568
    }
569

570
    if (_debugging) {
×
571
        LogDebug() << "Finding " << path << " in " << _root_dir;
×
572
    }
573
    if (path.rfind(_root_dir, 0) != 0) {
×
574
        LogWarn() << "FTP: invalid path " << path;
×
575
        response.opcode = Opcode::RSP_NAK;
×
576
        response.size = 1;
×
577
        response.data[0] = ServerResult::ERR_FAIL;
×
578
        _send_mavlink_ftp_message(response);
×
579
        return;
×
580
    }
581

582
    if (_debugging) {
×
583
        LogDebug() << "Going to open writeonly: " << path;
×
584
    }
585

586
    // fail only if requested open for read
587
    std::error_code ec;
×
588
    if (!fs::exists(path, ec)) {
×
589
        LogWarn() << "FTP: Open failed - file not found";
×
590
        response.opcode = Opcode::RSP_NAK;
×
591
        response.size = 1;
×
592
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
593
        _send_mavlink_ftp_message(response);
×
594
        return;
×
595
    }
596

597
    auto file_size = static_cast<uint32_t>(fs::file_size(path, ec));
×
598
    if (ec) {
×
599
        LogErr() << "Could not determine file size of '" << path << "': " << ec.message();
×
600
        return;
×
601
    }
602

603
    if (_debugging) {
×
604
        LogDebug() << "Determined filesize to be: " << file_size << " bytes";
×
605
    }
606

607
    std::ofstream ofstream;
×
608
    ofstream.open(path, std::ios::out | std::ios::binary);
×
609

610
    if (!ofstream.is_open()) {
×
611
        LogWarn() << "FTP: Open failed";
×
612
        response.opcode = Opcode::RSP_NAK;
×
613
        response.size = 1;
×
614
        response.data[0] = ServerResult::ERR_FAIL;
×
615
        _send_mavlink_ftp_message(response);
×
616
        return;
×
617
    }
618

619
    _session_info.ofstream = std::move(ofstream);
×
620
    _session_info.file_size = file_size;
×
621

622
    response.opcode = Opcode::RSP_ACK;
×
623
    response.session = 0;
×
624
    response.size = sizeof(uint32_t);
×
625
    std::memcpy(response.data, &file_size, response.size);
×
626

627
    _send_mavlink_ftp_message(response);
×
628
}
×
629

630
void MavlinkFtpServer::_work_create_file(const PayloadHeader& payload)
7✔
631
{
632
    auto response = PayloadHeader{};
7✔
633
    response.seq_number = payload.seq_number + 1;
7✔
634
    response.req_opcode = payload.opcode;
7✔
635

636
    std::lock_guard<std::mutex> lock(_mutex);
7✔
637
    if (_session_info.ofstream.is_open()) {
7✔
638
        _reset();
1✔
639
    }
640

641
    std::string path;
7✔
642
    {
643
        std::lock_guard<std::mutex> tmp_lock(_tmp_files_mutex);
7✔
644
        const auto it = _tmp_files.find(_data_as_string(payload));
7✔
645
        if (it != _tmp_files.end()) {
7✔
646
            path = it->second;
×
647
        } else {
648
            auto maybe_path = _path_from_payload(payload);
7✔
649
            if (std::holds_alternative<ServerResult>(maybe_path)) {
7✔
650
                response.opcode = Opcode::RSP_NAK;
2✔
651
                response.size = 1;
2✔
652
                response.data[0] = std::get<ServerResult>(maybe_path);
2✔
653
                _send_mavlink_ftp_message(response);
2✔
654
                return;
2✔
655
            }
656

657
            path = std::get<std::string>(maybe_path);
5✔
658
        }
7✔
659
    }
7✔
660

661
    if (path.empty()) {
5✔
662
        response.opcode = Opcode::RSP_NAK;
×
663
        response.size = 1;
×
664
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
665
        _send_mavlink_ftp_message(response);
×
666
        return;
×
667
    }
668

669
    if (_debugging) {
5✔
670
        LogInfo() << "Finding " << path << " in " << _root_dir;
×
671
    }
672
    if (path.rfind(_root_dir, 0) != 0) {
5✔
673
        LogWarn() << "FTP: invalid path " << path;
×
674
        response.opcode = Opcode::RSP_NAK;
×
675
        response.size = 1;
×
676
        response.data[0] = ServerResult::ERR_FAIL;
×
677
        _send_mavlink_ftp_message(response);
×
678
        return;
×
679
    }
680

681
    if (_debugging) {
5✔
682
        LogDebug() << "Creating file: " << path;
×
683
    }
684

685
    std::ofstream ofstream;
5✔
686
    ofstream.open(path, std::ios::out | std::ios::binary);
5✔
687

688
    if (!ofstream.is_open()) {
5✔
689
        LogWarn() << "FTP: Open failed";
×
690
        response.opcode = Opcode::RSP_NAK;
×
691
        response.size = 1;
×
692
        response.data[0] = ServerResult::ERR_FAIL;
×
693
        _send_mavlink_ftp_message(response);
×
694
        return;
×
695
    }
696

697
    _session_info.ofstream = std::move(ofstream);
5✔
698
    _session_info.file_size = 0;
5✔
699

700
    response.session = 0;
5✔
701
    response.size = 0;
5✔
702
    response.opcode = Opcode::RSP_ACK;
5✔
703

704
    _send_mavlink_ftp_message(response);
5✔
705
}
9✔
706

707
void MavlinkFtpServer::_work_read(const PayloadHeader& payload)
304✔
708
{
709
    auto response = PayloadHeader{};
304✔
710
    response.seq_number = payload.seq_number + 1;
304✔
711
    response.req_opcode = payload.opcode;
304✔
712

713
    std::lock_guard<std::mutex> lock(_mutex);
304✔
714
    if (payload.session != 0 || !_session_info.ifstream.is_open()) {
304✔
715
        _reset();
×
716
    }
717

718
    // We have to test seek past EOF ourselves, lseek will allow seek past EOF
719
    if (payload.offset >= _session_info.file_size) {
304✔
720
        response.opcode = Opcode::RSP_NAK;
×
721
        response.size = 1;
×
722
        response.data[0] = ServerResult::ERR_EOF;
×
723
        if (_debugging) {
×
724
            LogDebug() << "Reached EOF reading";
×
725
        }
726
        _send_mavlink_ftp_message(response);
×
727
        return;
×
728
    }
729

730
    _session_info.ifstream.seekg(payload.offset);
304✔
731
    if (_session_info.ifstream.fail()) {
304✔
732
        response.opcode = Opcode::RSP_NAK;
×
733
        response.size = 1;
×
734
        response.data[0] = ServerResult::ERR_FAIL;
×
735
        LogWarn() << "Seek failed";
×
736
        _send_mavlink_ftp_message(response);
×
737
        return;
×
738
    }
739

740
    if (_debugging) {
304✔
741
        LogWarn() << "Read at " << payload.offset << " for " << int(payload.size);
×
742
    }
743

744
    _session_info.ifstream.read(reinterpret_cast<char*>(response.data), payload.size);
304✔
745

746
    if (_session_info.ifstream.fail()) {
304✔
747
        response.opcode = Opcode::RSP_NAK;
×
748
        response.size = 1;
×
749
        response.data[0] = ServerResult::ERR_FAIL;
×
750
        LogWarn() << "Read failed";
×
751
        _send_mavlink_ftp_message(response);
×
752
        return;
×
753
    }
754

755
    const uint32_t bytes_read = _session_info.ifstream.gcount();
304✔
756

757
    response.offset = payload.offset;
304✔
758
    response.size = bytes_read;
304✔
759
    response.opcode = Opcode::RSP_ACK;
304✔
760

761
    _send_mavlink_ftp_message(response);
304✔
762
}
304✔
763

764
void MavlinkFtpServer::_work_burst(const PayloadHeader& payload)
8✔
765
{
766
    auto response = PayloadHeader{};
8✔
767
    response.req_opcode = payload.opcode;
8✔
768

769
    std::lock_guard<std::mutex> lock(_mutex);
8✔
770
    if (payload.session != 0 || !_session_info.ifstream.is_open()) {
8✔
771
        _reset();
×
772
    }
773

774
    // We have to test seek past EOF ourselves, lseek will allow seek past EOF
775
    if (payload.offset >= _session_info.file_size) {
8✔
776
        response.seq_number = payload.seq_number + 1;
×
777
        response.opcode = Opcode::RSP_NAK;
×
778
        response.size = 1;
×
779
        response.data[0] = ServerResult::ERR_EOF;
×
780
        if (_debugging) {
×
781
            LogDebug() << "Reached EOF reading";
×
782
        }
783
        _send_mavlink_ftp_message(response);
×
784
        return;
×
785
    }
786

787
    if (_debugging) {
8✔
788
        LogDebug() << "Seek to " << payload.offset;
×
789
    }
790
    _session_info.ifstream.seekg(payload.offset);
8✔
791
    if (_session_info.ifstream.fail()) {
8✔
792
        response.seq_number = payload.seq_number + 1;
×
793
        response.opcode = Opcode::RSP_NAK;
×
794
        response.size = 1;
×
795
        response.data[0] = ServerResult::ERR_FAIL;
×
796
        LogErr() << "Seek failed";
×
797
        _send_mavlink_ftp_message(response);
×
798
        return;
×
799
    }
800

801
    _session_info.burst_offset = payload.offset;
8✔
802
    _session_info.burst_chunk_size = payload.size;
8✔
803
    _burst_seq = payload.seq_number + 1;
8✔
804

805
    if (_session_info.burst_thread.joinable()) {
8✔
806
        _session_info.burst_stop = true;
×
807
        _session_info.burst_thread.join();
×
808
    }
809

810
    _session_info.burst_stop = false;
8✔
811

812
    // Schedule sending out burst messages.
813
    _session_info.burst_thread = std::thread([this]() {
16✔
814
        while (!_session_info.burst_stop)
282✔
815
            if (_send_burst_packet())
282✔
816
                break;
8✔
817
    });
8✔
818

819
    // Don't send response as that's done in the call every burst call above.
820
}
8✔
821

822
// Returns true if sending is complete
823
bool MavlinkFtpServer::_send_burst_packet()
282✔
824
{
825
    std::lock_guard<std::mutex> lock(_mutex);
282✔
826
    if (!_session_info.ifstream.is_open()) {
282✔
827
        return false;
×
828
    }
829

830
    PayloadHeader burst_packet{};
282✔
831
    burst_packet.req_opcode = Opcode::CMD_BURST_READ_FILE;
282✔
832
    burst_packet.seq_number = _burst_seq++;
282✔
833

834
    _make_burst_packet(burst_packet);
282✔
835

836
    _send_mavlink_ftp_message(burst_packet);
282✔
837

838
    if (burst_packet.burst_complete == 1) {
282✔
839
        return true;
8✔
840
    }
841

842
    return false;
274✔
843
}
282✔
844

845
void MavlinkFtpServer::_make_burst_packet(PayloadHeader& packet)
282✔
846
{
847
    uint32_t bytes_to_read = std::min(
282✔
848
        static_cast<uint32_t>(_session_info.burst_chunk_size),
282✔
849
        _session_info.file_size - _session_info.burst_offset);
564✔
850

851
    if (_debugging) {
282✔
852
        LogDebug() << "Burst read of " << bytes_to_read << " bytes";
×
853
    }
854
    _session_info.ifstream.read(reinterpret_cast<char*>(packet.data), bytes_to_read);
282✔
855

856
    if (_session_info.ifstream.fail()) {
282✔
857
        packet.opcode = Opcode::RSP_NAK;
×
858
        packet.size = 1;
×
859
        packet.data[0] = ServerResult::ERR_FAIL;
×
860
        LogWarn() << "Burst read failed";
×
861
        return;
×
862
    }
863

864
    const uint32_t bytes_read = _session_info.ifstream.gcount();
282✔
865
    packet.size = bytes_read;
282✔
866
    packet.opcode = Opcode::RSP_ACK;
282✔
867

868
    packet.offset = _session_info.burst_offset;
282✔
869
    _session_info.burst_offset += bytes_read;
282✔
870

871
    if (_session_info.burst_offset == _session_info.file_size) {
282✔
872
        // Last read, we are done for this burst.
873
        packet.burst_complete = 1;
8✔
874
        if (_debugging) {
8✔
875
            LogDebug() << "Burst complete";
×
876
        }
877
    }
878
}
879

880
void MavlinkFtpServer::_work_write(const PayloadHeader& payload)
98✔
881
{
882
    auto response = PayloadHeader{};
98✔
883
    response.seq_number = payload.seq_number + 1;
98✔
884
    response.req_opcode = payload.opcode;
98✔
885

886
    std::lock_guard<std::mutex> lock(_mutex);
98✔
887
    if (payload.session != 0 && !_session_info.ofstream.is_open()) {
98✔
888
        _reset();
×
889
    }
890

891
    _session_info.ofstream.seekp(payload.offset);
98✔
892
    if (_session_info.ifstream.fail()) {
98✔
893
        response.opcode = Opcode::RSP_NAK;
×
894
        response.size = 1;
×
895
        response.data[0] = ServerResult::ERR_FAIL;
×
896
        LogWarn() << "Seek failed";
×
897
        _send_mavlink_ftp_message(response);
×
898
        return;
×
899
    }
900

901
    _session_info.ofstream.write(reinterpret_cast<const char*>(payload.data), payload.size);
98✔
902
    if (_session_info.ofstream.fail()) {
98✔
903
        response.opcode = Opcode::RSP_NAK;
×
904
        response.size = 1;
×
905
        response.data[0] = ServerResult::ERR_FAIL;
×
906
        LogWarn() << "Write failed";
×
907
        _send_mavlink_ftp_message(response);
×
908
        return;
×
909
    }
910

911
    response.opcode = Opcode::RSP_ACK;
98✔
912
    response.size = 0;
98✔
913

914
    _send_mavlink_ftp_message(response);
98✔
915
}
98✔
916

917
void MavlinkFtpServer::_work_terminate(const PayloadHeader& payload)
29✔
918
{
919
    {
920
        std::lock_guard<std::mutex> lock(_mutex);
29✔
921
        _reset();
29✔
922
    }
29✔
923

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

932
void MavlinkFtpServer::_reset()
120✔
933
{
934
    // requires lock
935
    if (_session_info.ifstream.is_open()) {
120✔
936
        _session_info.ifstream.close();
14✔
937
    }
938

939
    if (_session_info.ofstream.is_open()) {
120✔
940
        _session_info.ofstream.close();
5✔
941
    }
942

943
    _session_info.burst_stop = true;
120✔
944
    if (_session_info.burst_thread.joinable()) {
120✔
945
        _session_info.burst_thread.join();
8✔
946
    }
947
}
120✔
948

949
void MavlinkFtpServer::_work_reset(const PayloadHeader& payload)
×
950
{
951
    {
952
        std::lock_guard<std::mutex> lock(_mutex);
×
953
        _reset();
×
954
    }
×
955

956
    auto response = PayloadHeader{};
×
957
    response.seq_number = payload.seq_number + 1;
×
958
    response.req_opcode = payload.opcode;
×
959
    response.opcode = Opcode::RSP_ACK;
×
960
    response.size = 0;
×
961
    _send_mavlink_ftp_message(response);
×
962
}
×
963

964
void MavlinkFtpServer::_work_remove_directory(const PayloadHeader& payload)
2✔
965
{
966
    auto response = PayloadHeader{};
2✔
967
    response.seq_number = payload.seq_number + 1;
2✔
968
    response.req_opcode = payload.opcode;
2✔
969

970
    std::lock_guard<std::mutex> lock(_mutex);
2✔
971

972
    auto maybe_path = _path_from_payload(payload);
2✔
973
    if (std::holds_alternative<ServerResult>(maybe_path)) {
2✔
974
        response.opcode = Opcode::RSP_NAK;
×
975
        response.size = 1;
×
976
        response.data[0] = std::get<ServerResult>(maybe_path);
×
977
        _send_mavlink_ftp_message(response);
×
978
        return;
×
979
    }
980

981
    fs::path path = std::get<std::string>(maybe_path);
2✔
982

983
    std::error_code ec;
2✔
984
    if (!fs::exists(path, ec)) {
2✔
985
        response.opcode = Opcode::RSP_NAK;
×
986
        response.size = 1;
×
987
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
988
        _send_mavlink_ftp_message(response);
×
989
        return;
×
990
    }
991
    if (ec) {
2✔
NEW
992
        LogErr() << "fs::exists for " << path << " returned error: " << ec.message();
×
UNCOV
993
        response.opcode = Opcode::RSP_NAK;
×
UNCOV
994
        response.size = 1;
×
UNCOV
995
        response.data[0] = ServerResult::ERR_FAIL;
×
NEW
996
        _send_mavlink_ftp_message(response);
×
NEW
997
        return;
×
998
    }
999

1000
    if (!fs::remove(path, ec)) {
2✔
1001
        LogErr() << "fs::remove returned error: " << ec.message();
1✔
1002
        response.opcode = Opcode::RSP_NAK;
1✔
1003
        response.size = 1;
1✔
1004
        response.data[0] = ServerResult::ERR_FAIL;
1✔
1005
        _send_mavlink_ftp_message(response);
1✔
1006
        return;
1✔
1007
    }
1008

1009
    response.opcode = Opcode::RSP_ACK;
1✔
1010
    response.size = 0;
1✔
1011
    _send_mavlink_ftp_message(response);
1✔
1012
}
4✔
1013

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

1020
    std::lock_guard<std::mutex> lock(_mutex);
3✔
1021

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

1031
    auto path = std::get<std::string>(maybe_path);
1✔
1032

1033
    std::error_code ec;
1✔
1034
    if (fs::exists(path, ec)) {
1✔
1035
        response.opcode = Opcode::RSP_NAK;
×
1036
        response.size = 1;
×
1037
        response.data[0] = ServerResult::ERR_FAIL_FILE_EXISTS;
×
1038
        _send_mavlink_ftp_message(response);
×
1039
        return;
×
1040
    }
1041

1042
    if (fs::create_directory(path, ec)) {
1✔
1043
        response.opcode = Opcode::RSP_ACK;
1✔
1044
    } else {
1045
        response.opcode = Opcode::RSP_NAK;
×
1046
        response.size = 2;
×
1047
        response.data[0] = ServerResult::ERR_FAIL_ERRNO;
×
1048
        response.data[1] = static_cast<uint8_t>(ec.value());
×
1049
    }
1050

1051
    _send_mavlink_ftp_message(response);
1✔
1052
}
5✔
1053

1054
void MavlinkFtpServer::_work_remove_file(const PayloadHeader& payload)
4✔
1055
{
1056
    auto response = PayloadHeader{};
4✔
1057
    response.seq_number = payload.seq_number + 1;
4✔
1058
    response.req_opcode = payload.opcode;
4✔
1059

1060
    std::lock_guard<std::mutex> lock(_mutex);
4✔
1061

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

1071
    auto path = std::get<std::string>(maybe_path);
2✔
1072

1073
    std::error_code ec;
2✔
1074
    if (!fs::exists(path, ec)) {
2✔
1075
        response.opcode = Opcode::RSP_NAK;
1✔
1076
        response.size = 1;
1✔
1077
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
1✔
1078
        _send_mavlink_ftp_message(response);
1✔
1079
        return;
1✔
1080
    }
1081
    if (fs::remove(path, ec)) {
1✔
1082
        response.opcode = Opcode::RSP_ACK;
1✔
1083
    } else {
1084
        response.opcode = Opcode::RSP_NAK;
×
1085
        response.size = 1;
×
1086
        response.data[0] = ServerResult::ERR_FAIL;
×
1087
    }
1088

1089
    _send_mavlink_ftp_message(response);
1✔
1090
}
8✔
1091

1092
void MavlinkFtpServer::_work_rename(const PayloadHeader& payload)
2✔
1093
{
1094
    auto response = PayloadHeader{};
2✔
1095
    response.seq_number = payload.seq_number + 1;
2✔
1096
    response.req_opcode = payload.opcode;
2✔
1097

1098
    std::lock_guard<std::mutex> lock(_mutex);
2✔
1099

1100
    auto maybe_old_name = _path_from_payload(payload, 0);
2✔
1101

1102
    if (std::holds_alternative<ServerResult>(maybe_old_name)) {
2✔
1103
        response.opcode = Opcode::RSP_NAK;
1✔
1104
        response.size = 1;
1✔
1105
        response.data[0] = std::get<ServerResult>(maybe_old_name);
1✔
1106
        _send_mavlink_ftp_message(response);
1✔
1107
        return;
1✔
1108
    }
1109

1110
    auto old_name = std::get<std::string>(maybe_old_name);
1✔
1111

1112
    auto maybe_new_name = _path_from_payload(payload, 1);
1✔
1113

1114
    if (std::holds_alternative<ServerResult>(maybe_new_name)) {
1✔
1115
        response.opcode = Opcode::RSP_NAK;
×
1116
        response.size = 1;
×
1117
        response.data[0] = std::get<ServerResult>(maybe_new_name);
×
1118
        _send_mavlink_ftp_message(response);
×
1119
        return;
×
1120
    }
1121

1122
    auto new_name = std::get<std::string>(maybe_new_name);
1✔
1123

1124
    if (_debugging) {
1✔
1125
        LogDebug() << "Rename from old_name " << old_name << " to " << new_name;
×
1126
    }
1127

1128
    std::error_code ec;
1✔
1129
    if (!fs::exists(old_name, ec)) {
1✔
1130
        response.opcode = Opcode::RSP_NAK;
×
1131
        response.size = 1;
×
1132
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
1133
        _send_mavlink_ftp_message(response);
×
1134
        return;
×
1135
    }
1136

1137
    fs::rename(old_name, new_name, ec);
1✔
1138
    if (ec) {
1✔
NEW
1139
        LogErr() << "fs::rename from " << old_name << " to " << new_name
×
NEW
1140
                 << " returned error: " << ec.message();
×
1141
        response.opcode = Opcode::RSP_NAK;
×
1142
        response.size = 1;
×
1143
        response.data[0] = ServerResult::ERR_FAIL;
×
NEW
1144
        _send_mavlink_ftp_message(response);
×
NEW
1145
        return;
×
1146
    }
1147

1148
    response.opcode = Opcode::RSP_ACK;
1✔
1149
    _send_mavlink_ftp_message(response);
1✔
1150
}
3✔
1151

1152
MavlinkFtpServer::ServerResult
1153
MavlinkFtpServer::_calc_local_file_crc32(const std::string& path, uint32_t& csum)
2✔
1154
{
1155
    std::error_code ec;
2✔
1156
    if (!fs::exists(path, ec)) {
2✔
1157
        return ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
1158
    }
1159

1160
    std::ifstream ifstream;
2✔
1161
    ifstream.open(path, std::ios::in | std::ios::binary);
2✔
1162

1163
    if (!ifstream.is_open()) {
2✔
1164
        return ServerResult::ERR_FILE_IO_ERROR;
×
1165
    }
1166

1167
    // Read whole file in buffer size chunks
1168
    Crc32 checksum;
2✔
1169
    char buffer[18392];
2✔
1170
    do {
1171
        ifstream.read(buffer, sizeof(buffer));
2✔
1172

1173
        if (ifstream.fail() && !ifstream.eof()) {
2✔
1174
            ifstream.close();
×
1175
            return ServerResult::ERR_FILE_IO_ERROR;
×
1176
        }
1177

1178
        auto bytes_read = ifstream.gcount();
2✔
1179
        checksum.add((uint8_t*)buffer, bytes_read);
2✔
1180

1181
    } while (!ifstream.eof());
2✔
1182

1183
    ifstream.close();
2✔
1184

1185
    csum = checksum.get();
2✔
1186

1187
    return ServerResult::SUCCESS;
2✔
1188
}
2✔
1189

1190
void MavlinkFtpServer::_work_calc_file_CRC32(const PayloadHeader& payload)
3✔
1191
{
1192
    auto response = PayloadHeader{};
3✔
1193
    response.seq_number = payload.seq_number + 1;
3✔
1194
    response.req_opcode = payload.opcode;
3✔
1195

1196
    std::lock_guard<std::mutex> lock(_mutex);
3✔
1197

1198
    auto maybe_path = _path_from_payload(payload);
3✔
1199
    if (std::holds_alternative<ServerResult>(maybe_path)) {
3✔
1200
        response.opcode = Opcode::RSP_NAK;
1✔
1201
        response.size = 1;
1✔
1202
        response.data[0] = std::get<ServerResult>(maybe_path);
1✔
1203
        _send_mavlink_ftp_message(response);
1✔
1204
        return;
1✔
1205
    }
1206

1207
    auto path = std::get<std::string>(maybe_path);
2✔
1208

1209
    std::error_code ec;
2✔
1210
    if (!fs::exists(path, ec)) {
2✔
1211
        response.opcode = Opcode::RSP_NAK;
×
1212
        response.size = 1;
×
1213
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
1214
        _send_mavlink_ftp_message(response);
×
1215
        return;
×
1216
    }
1217

1218
    uint32_t checksum;
2✔
1219
    ServerResult res = _calc_local_file_crc32(path, checksum);
2✔
1220
    if (res != ServerResult::SUCCESS) {
2✔
1221
        response.opcode = Opcode::RSP_NAK;
×
1222
        response.size = 1;
×
1223
        response.data[0] = res;
×
1224
        _send_mavlink_ftp_message(response);
×
1225
        return;
×
1226
    }
1227

1228
    response.opcode = Opcode::RSP_ACK;
2✔
1229
    response.size = sizeof(uint32_t);
2✔
1230
    std::memcpy(response.data, &checksum, response.size);
2✔
1231

1232
    _send_mavlink_ftp_message(response);
2✔
1233
}
4✔
1234

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