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

mavlink / MAVSDK / 6739182515

02 Nov 2023 11:04PM UTC coverage: 36.952% (+5.7%) from 31.229%
6739182515

push

github

web-flow
Merge pull request #2060 from mavlink/pr-split-ftp

Split Ftp plugin into Ftp and FtpServer

2002 of 2573 new or added lines in 26 files covered. (77.81%)

3 existing lines in 3 files now uncovered.

9920 of 26846 relevant lines covered (36.95%)

112.43 hits per line

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

59.68
/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) :
68✔
16
    _server_component_impl(server_component_impl)
68✔
17
{
18
    if (const char* env_p = std::getenv("MAVSDK_FTP_DEBUGGING")) {
68✔
NEW
19
        if (std::string(env_p) == "1") {
×
NEW
20
            LogDebug() << "Ftp debugging is on.";
×
NEW
21
            _debugging = true;
×
22
        }
23
    }
24

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

149
            case Opcode::CMD_REMOVE_FILE:
4✔
150
                if (_debugging) {
4✔
NEW
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✔
NEW
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✔
NEW
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✔
NEW
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✔
NEW
179
                    LogDebug() << "OPC:CMD_CALC_FILE_CRC32";
×
180
                }
181
                _work_calc_file_CRC32(payload);
3✔
182
                break;
3✔
183

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

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

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

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

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

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

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

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

236
    return result;
68✔
237
}
238

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

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

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

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

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

261
    // We strip leading slashes (like absolute paths).
262
    if (temp_path.size() >= 1 && temp_path[0] == '/') {
38✔
NEW
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();
190✔
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());
38✔
271
    if (ret.first != _root_dir.end()) {
38✔
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();
34✔
278
}
279

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

284
    std::error_code ignored;
24✔
285
    _root_dir = fs::canonical(fs::path(root_dir), ignored).string();
24✔
286
    if (_debugging) {
24✔
NEW
287
        LogDebug() << "Set root dir to: " << _root_dir;
×
288
    }
289
}
24✔
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✔
NEW
317
        LogWarn() << "FTP: can't open path " << path;
×
318
        // this is not an FTP error, abort directory by simulating eof
NEW
319
        response.opcode = Opcode::RSP_NAK;
×
NEW
320
        response.size = 1;
×
NEW
321
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
NEW
322
        _send_mavlink_ftp_message(response);
×
NEW
323
        return;
×
324
    }
325

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

330
    for (const auto& entry : fs::directory_iterator(fs::canonical(path))) {
1,254✔
331
        if (requested_offset > 0) {
1,224✔
332
            requested_offset--;
1,016✔
333
            continue;
1,016✔
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✔
NEW
341
            LogWarn() << "Could not determine whether '" << entry.path().string()
×
NEW
342
                      << "' is a file: " << ec.message();
×
NEW
343
            continue;
×
344
        }
345

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

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

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

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

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

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

378
        } else {
379
            // Ignore all other types.
NEW
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
    }
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
}
408

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

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

420
    std::string path;
14✔
421
    {
422
        std::lock_guard<std::mutex> tmp_lock(_tmp_files_mutex);
14✔
423
        const auto it = _tmp_files.find(_data_as_string(payload));
14✔
424
        if (it != _tmp_files.end()) {
14✔
NEW
425
            path = it->second;
×
426
        } else {
427
            auto maybe_path = _path_from_payload(payload);
14✔
428
            if (std::holds_alternative<ServerResult>(maybe_path)) {
14✔
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);
10✔
437
        }
438
    }
439

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

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

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

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

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

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

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

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

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

497
    _send_mavlink_ftp_message(response);
10✔
498
}
499

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

NEW
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✔
NEW
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
        }
629
    }
630

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

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

651
    if (_debugging) {
5✔
NEW
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✔
NEW
659
        LogWarn() << "FTP: Open failed";
×
NEW
660
        response.opcode = Opcode::RSP_NAK;
×
NEW
661
        response.size = 1;
×
NEW
662
        response.data[0] = ServerResult::ERR_FAIL;
×
NEW
663
        _send_mavlink_ftp_message(response);
×
NEW
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
}
676

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

683
    std::lock_guard<std::mutex> lock(_mutex);
262✔
684
    if (payload.session != 0 || !_session_info.ifstream.is_open()) {
262✔
NEW
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) {
262✔
NEW
690
        response.opcode = Opcode::RSP_NAK;
×
NEW
691
        response.size = 1;
×
NEW
692
        response.data[0] = ServerResult::ERR_EOF;
×
NEW
693
        if (_debugging) {
×
NEW
694
            LogDebug() << "Reached EOF reading";
×
695
        }
NEW
696
        _send_mavlink_ftp_message(response);
×
NEW
697
        return;
×
698
    }
699

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

710
    _session_info.ifstream.read(reinterpret_cast<char*>(response.data), payload.size);
262✔
711

712
    if (_session_info.ifstream.fail()) {
262✔
NEW
713
        response.opcode = Opcode::RSP_NAK;
×
NEW
714
        response.size = 1;
×
NEW
715
        response.data[0] = ServerResult::ERR_FAIL;
×
NEW
716
        LogWarn() << "Read failed";
×
NEW
717
        _send_mavlink_ftp_message(response);
×
NEW
718
        return;
×
719
    }
720

721
    const uint32_t bytes_read = _session_info.ifstream.gcount();
262✔
722

723
    response.size = bytes_read;
262✔
724
    response.opcode = Opcode::RSP_ACK;
262✔
725

726
    _send_mavlink_ftp_message(response);
262✔
727
}
728

729
void MavlinkFtpServer::_work_burst(const PayloadHeader& payload)
15✔
730
{
731
    auto response = PayloadHeader{};
15✔
732
    response.req_opcode = payload.opcode;
15✔
733

734
    std::lock_guard<std::mutex> lock(_mutex);
15✔
735
    if (payload.session != 0 || !_session_info.ifstream.is_open()) {
15✔
NEW
736
        _reset();
×
737
    }
738

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

752
    if (_debugging) {
15✔
NEW
753
        LogDebug() << "Seek to " << payload.offset;
×
754
    }
755
    _session_info.ifstream.seekg(payload.offset);
15✔
756
    if (_session_info.ifstream.fail()) {
15✔
NEW
757
        response.seq_number = payload.seq_number + 1;
×
NEW
758
        response.opcode = Opcode::RSP_NAK;
×
NEW
759
        response.size = 1;
×
NEW
760
        response.data[0] = ServerResult::ERR_FAIL;
×
NEW
761
        LogErr() << "Seek failed";
×
NEW
762
        _send_mavlink_ftp_message(response);
×
NEW
763
        return;
×
764
    }
765

766
    _session_info.burst_offset = payload.offset;
15✔
767

768
    if (payload.size != 4) {
15✔
NEW
769
        response.seq_number = payload.seq_number + 1;
×
NEW
770
        response.opcode = Opcode::RSP_NAK;
×
NEW
771
        response.size = 1;
×
NEW
772
        response.data[0] = ServerResult::ERR_INVALID_DATA_SIZE;
×
NEW
773
        LogErr() << "Burst size invalid";
×
NEW
774
        _send_mavlink_ftp_message(response);
×
NEW
775
        return;
×
776
    }
777

778
    uint32_t burst_size;
15✔
779
    std::memcpy(&burst_size, &payload.data, payload.size);
15✔
780
    _session_info.burst_end = _session_info.burst_offset + burst_size;
15✔
781

782
    _burst_seq = payload.seq_number + 1;
15✔
783

784
    // Schedule sending out burst messages.
785
    // Use some arbitrary "fast" rate: 100 packets per second
786
    _server_component_impl.add_call_every(
15✔
787
        [this]() { _send_burst_packet(); }, 0.01f, &_burst_call_every_cookie);
273✔
788

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

792
void MavlinkFtpServer::_send_burst_packet()
273✔
793
{
794
    std::lock_guard<std::mutex> lock(_mutex);
546✔
795
    if (!_session_info.ifstream.is_open()) {
273✔
NEW
796
        _reset();
×
797
    }
798

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

803
    _make_burst_packet(burst_packet);
273✔
804

805
    _send_mavlink_ftp_message(burst_packet);
273✔
806

807
    if (burst_packet.burst_complete == 1) {
273✔
808
        if (_burst_call_every_cookie != nullptr) {
15✔
809
            _server_component_impl.remove_call_every(_burst_call_every_cookie);
15✔
810
            _burst_call_every_cookie = nullptr;
15✔
811
        }
812
    }
813
}
273✔
814

815
void MavlinkFtpServer::_make_burst_packet(PayloadHeader& packet)
273✔
816
{
817
    uint32_t bytes_to_read = std::min(
273✔
818
        static_cast<uint32_t>(max_data_length),
546✔
819
        _session_info.burst_end - _session_info.burst_offset);
273✔
820

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

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

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

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

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

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

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

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

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

881
    response.opcode = Opcode::RSP_ACK;
93✔
882
    response.size = sizeof(uint32_t);
93✔
883
    std::memcpy(response.data, &payload.size, response.size);
93✔
884

885
    _send_mavlink_ftp_message(response);
93✔
886
}
887

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

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

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

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

914
    if (_burst_call_every_cookie != nullptr) {
83✔
NEW
915
        _server_component_impl.remove_call_every(_burst_call_every_cookie);
×
NEW
916
        _burst_call_every_cookie = nullptr;
×
917
    }
918
}
83✔
919

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

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

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

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

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

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

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

971
    _send_mavlink_ftp_message(response);
2✔
972
}
973

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

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

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

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

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

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

1011
    _send_mavlink_ftp_message(response);
1✔
1012
}
1013

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

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

1022
    auto maybe_path = _path_from_payload(payload);
4✔
1023
    if (std::holds_alternative<ServerResult>(maybe_path)) {
4✔
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);
2✔
1032

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

1049
    _send_mavlink_ftp_message(response);
1✔
1050
}
1051

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

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

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

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

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

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

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

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

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

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

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

1106
    _send_mavlink_ftp_message(response);
1✔
1107
}
1108

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

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

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

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

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

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

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

1140
    ifstream.close();
2✔
1141

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

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

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

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

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

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

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

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

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

1189
    _send_mavlink_ftp_message(response);
2✔
1190
}
1191

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