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

mavlink / MAVSDK / 11943405545

20 Nov 2024 11:16PM UTC coverage: 38.691% (-0.02%) from 38.707%
11943405545

push

github

web-flow
Merge pull request #2446 from mavlink/pr-ftp-warning

core: remove way too verbose warnings

2 of 8 new or added lines in 2 files covered. (25.0%)

5 existing lines in 3 files now uncovered.

12076 of 31211 relevant lines covered (38.69%)

247.13 hits per line

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

61.25
/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,176✔
28
        this);
29
}
72✔
30

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

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

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

54
    if (ftp_req.target_component != 0 &&
2,352✔
55
        ftp_req.target_component != _server_component_impl.get_own_component_id()) {
1,176✔
56
        if (_debugging) {
9✔
NEW
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,167✔
63

64
    // Basic sanity check: validate length before use.
65
    if (payload.size > max_data_length) {
1,167✔
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,167✔
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,167✔
81
        _target_component_id = msg.compid;
1,167✔
82

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

90
            case Opcode::CMD_TERMINATE_SESSION:
31✔
91
                if (_debugging) {
31✔
92
                    LogDebug() << "OPC:CMD_TERMINATE_SESSION";
×
93
                }
94
                _work_terminate(payload);
31✔
95
                break;
31✔
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:
17✔
112
                if (_debugging) {
17✔
113
                    LogDebug() << "OPC:CMD_OPEN_FILE_RO";
×
114
                }
115
                _work_open_file_readonly(payload);
17✔
116
                break;
17✔
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:
274✔
133
                if (_debugging) {
274✔
134
                    LogDebug() << "OPC:CMD_READ_FILE";
×
135
                }
136
                _work_read(payload);
274✔
137
                break;
274✔
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:
95✔
147
                if (_debugging) {
95✔
148
                    LogDebug() << "OPC:CMD_WRITE_FILE";
×
149
                }
150
                _work_write(payload);
95✔
151
                break;
95✔
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:
710✔
189
                // Not for us, ignore it.
190
                return;
710✔
191
        }
192
    }
193
}
194

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

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

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

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

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

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

237
    result.resize(end - start);
74✔
238
    std::memcpy(result.data(), &payload.data[start], end - start);
74✔
239

240
    return result;
74✔
241
}
242

243
std::variant<std::string, MavlinkFtpServer::ServerResult>
244
MavlinkFtpServer::_path_from_payload(const PayloadHeader& payload, size_t entry)
50✔
245
{
246
    // Requires lock
247

248
    auto data = _data_as_string(payload, entry);
50✔
249
    return _path_from_string(data);
50✔
250
}
50✔
251

252
std::variant<std::string, MavlinkFtpServer::ServerResult>
253
MavlinkFtpServer::_path_from_string(const std::string& payload_path)
50✔
254
{
255
    // Requires lock
256

257
    // No permission whatsoever if the root dir is not set.
258
    if (_root_dir.empty()) {
50✔
259
        return ServerResult::ERR_FAIL;
9✔
260
    }
261

262
    // Take a copy before we mess with it.
263
    auto temp_path = payload_path;
41✔
264

265
    // We strip leading slashes (like absolute paths).
266
    if (temp_path.size() >= 1 && temp_path[0] == '/') {
41✔
267
        temp_path = temp_path.substr(1, temp_path.size());
×
268
    }
269

270
    fs::path combined_path = (fs::path(_root_dir) / temp_path).lexically_normal();
164✔
271

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

281
    return combined_path.string();
37✔
282
}
41✔
283

284
void MavlinkFtpServer::set_root_directory(const std::string& root_dir)
25✔
285
{
286
    std::lock_guard<std::mutex> lock(_mutex);
25✔
287

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

295
void MavlinkFtpServer::_work_list(const PayloadHeader& payload)
11✔
296
{
297
    auto response = PayloadHeader{};
11✔
298
    response.seq_number = payload.seq_number + 1;
11✔
299
    response.req_opcode = payload.opcode;
11✔
300

301
    std::lock_guard<std::mutex> lock(_mutex);
11✔
302

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

312
    fs::path path = std::get<std::string>(maybe_path);
10✔
313

314
    uint8_t offset = 0;
10✔
315

316
    // Move to the requested offset
317
    uint32_t requested_offset = payload.offset;
10✔
318

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

330
    if (_debugging) {
10✔
331
        LogDebug() << "Opening path: " << path.string();
×
332
    }
333

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

341
        std::string payload_str;
208✔
342

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

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

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

365
            if (_debugging) {
104✔
366
                LogDebug() << "Found file: " << name.string() << ", size: " << filesize << " bytes";
×
367
            }
368

369
            payload_str += 'F';
104✔
370
            payload_str += name.string();
104✔
371
            payload_str += '\t';
104✔
372
            payload_str += std::to_string(filesize);
104✔
373

374
        } else if (is_directory) {
104✔
375
            if (_debugging) {
104✔
376
                LogDebug() << "Found directory: " << name.string();
×
377
            }
378

379
            payload_str += 'D';
104✔
380
            payload_str += name.string();
104✔
381

382
        } else {
383
            // Ignore all other types.
384
            continue;
×
385
        }
386

387
        auto required_len = payload_str.length() + 1;
208✔
388

389
        // Do we have room for the dir entry and the null terminator?
390
        if (offset + required_len > max_data_length) {
208✔
391
            break;
8✔
392
        }
393

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

396
        offset += static_cast<uint8_t>(required_len);
200✔
397
    }
226✔
398

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

405
    } else {
406
        response.opcode = Opcode::RSP_ACK;
9✔
407
        response.size = offset;
9✔
408
    }
409

410
    _send_mavlink_ftp_message(response);
10✔
411
}
12✔
412

413
void MavlinkFtpServer::_work_open_file_readonly(const PayloadHeader& payload)
17✔
414
{
415
    auto response = PayloadHeader{};
17✔
416
    response.seq_number = payload.seq_number + 1;
17✔
417
    response.req_opcode = payload.opcode;
17✔
418

419
    std::lock_guard<std::mutex> lock(_mutex);
17✔
420
    if (_session_info.ifstream.is_open()) {
17✔
421
        _reset();
2✔
422
    }
423

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

440
            path = std::get<std::string>(maybe_path);
13✔
441
        }
17✔
442
    }
17✔
443

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

456
    if (_debugging) {
13✔
457
        LogDebug() << "Going to open readonly: " << path;
×
458
    }
459

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

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

476
    if (_debugging) {
13✔
477
        LogDebug() << "Determined filesize to be: " << file_size << " bytes";
×
478
    }
479

480
    std::ifstream ifstream;
13✔
481
    ifstream.open(path, std::ios::in | std::ios::binary);
13✔
482

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

492
    _session_info.ifstream = std::move(ifstream);
13✔
493
    _session_info.file_size = file_size;
13✔
494

495
    response.opcode = Opcode::RSP_ACK;
13✔
496
    response.session = 0;
13✔
497
    response.seq_number = payload.seq_number + 1;
13✔
498
    response.size = sizeof(uint32_t);
13✔
499
    std::memcpy(response.data, &file_size, response.size);
13✔
500

501
    _send_mavlink_ftp_message(response);
13✔
502
}
21✔
503

504
void MavlinkFtpServer::_work_open_file_writeonly(const PayloadHeader& payload)
×
505
{
506
    auto response = PayloadHeader{};
×
507
    response.seq_number = payload.seq_number + 1;
×
508
    response.req_opcode = payload.opcode;
×
509

510
    std::lock_guard<std::mutex> lock(_mutex);
×
511

512
    if (_session_info.ofstream.is_open()) {
×
513
        _reset();
×
514
    }
515

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

532
            path = std::get<std::string>(maybe_path);
×
533
        }
×
534
    }
×
535

536
    if (path.empty()) {
×
537
        response.opcode = Opcode::RSP_NAK;
×
538
        response.size = 1;
×
539
        response.data[0] = ServerResult::ERR_FAIL_FILE_DOES_NOT_EXIST;
×
540
        _send_mavlink_ftp_message(response);
×
541
        return;
×
542
    }
543

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

556
    if (_debugging) {
×
557
        LogDebug() << "Going to open writeonly: " << path;
×
558
    }
559

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

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

577
    if (_debugging) {
×
578
        LogDebug() << "Determined filesize to be: " << file_size << " bytes";
×
579
    }
580

581
    std::ofstream ofstream;
×
582
    ofstream.open(path, std::ios::out | std::ios::binary);
×
583

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

593
    _session_info.ofstream = std::move(ofstream);
×
594
    _session_info.file_size = file_size;
×
595

596
    response.opcode = Opcode::RSP_ACK;
×
597
    response.session = 0;
×
598
    response.size = sizeof(uint32_t);
×
599
    std::memcpy(response.data, &file_size, response.size);
×
600

601
    _send_mavlink_ftp_message(response);
×
602
}
×
603

604
void MavlinkFtpServer::_work_create_file(const PayloadHeader& payload)
7✔
605
{
606
    auto response = PayloadHeader{};
7✔
607
    response.seq_number = payload.seq_number + 1;
7✔
608
    response.req_opcode = payload.opcode;
7✔
609

610
    std::lock_guard<std::mutex> lock(_mutex);
7✔
611
    if (_session_info.ofstream.is_open()) {
7✔
612
        _reset();
1✔
613
    }
614

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

631
            path = std::get<std::string>(maybe_path);
5✔
632
        }
7✔
633
    }
7✔
634

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

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

655
    if (_debugging) {
5✔
656
        LogDebug() << "Creating file: " << path;
×
657
    }
658

659
    std::ofstream ofstream;
5✔
660
    ofstream.open(path, std::ios::out | std::ios::binary);
5✔
661

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

671
    _session_info.ofstream = std::move(ofstream);
5✔
672
    _session_info.file_size = 0;
5✔
673

674
    response.session = 0;
5✔
675
    response.size = 0;
5✔
676
    response.opcode = Opcode::RSP_ACK;
5✔
677

678
    _send_mavlink_ftp_message(response);
5✔
679
}
9✔
680

681
void MavlinkFtpServer::_work_read(const PayloadHeader& payload)
274✔
682
{
683
    auto response = PayloadHeader{};
274✔
684
    response.seq_number = payload.seq_number + 1;
274✔
685
    response.req_opcode = payload.opcode;
274✔
686

687
    std::lock_guard<std::mutex> lock(_mutex);
274✔
688
    if (payload.session != 0 || !_session_info.ifstream.is_open()) {
274✔
689
        _reset();
×
690
    }
691

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

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

714
    if (_debugging) {
274✔
715
        LogWarn() << "Read at " << payload.offset << " for " << int(payload.size);
×
716
    }
717

718
    _session_info.ifstream.read(reinterpret_cast<char*>(response.data), payload.size);
274✔
719

720
    if (_session_info.ifstream.fail()) {
274✔
721
        response.opcode = Opcode::RSP_NAK;
×
722
        response.size = 1;
×
723
        response.data[0] = ServerResult::ERR_FAIL;
×
724
        LogWarn() << "Read failed";
×
725
        _send_mavlink_ftp_message(response);
×
726
        return;
×
727
    }
728

729
    const uint32_t bytes_read = _session_info.ifstream.gcount();
274✔
730

731
    response.offset = payload.offset;
274✔
732
    response.size = bytes_read;
274✔
733
    response.opcode = Opcode::RSP_ACK;
274✔
734

735
    _send_mavlink_ftp_message(response);
274✔
736
}
274✔
737

738
void MavlinkFtpServer::_work_burst(const PayloadHeader& payload)
8✔
739
{
740
    auto response = PayloadHeader{};
8✔
741
    response.req_opcode = payload.opcode;
8✔
742

743
    std::lock_guard<std::mutex> lock(_mutex);
8✔
744
    if (payload.session != 0 || !_session_info.ifstream.is_open()) {
8✔
745
        _reset();
×
746
    }
747

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

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

775
    _session_info.burst_offset = payload.offset;
8✔
776
    _session_info.burst_chunk_size = payload.size;
8✔
777
    _burst_seq = payload.seq_number + 1;
8✔
778

779
    if (_session_info.burst_thread.joinable()) {
8✔
780
        _session_info.burst_stop = true;
×
781
        _session_info.burst_thread.join();
×
782
    }
783

784
    _session_info.burst_stop = false;
8✔
785

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

793
    // Don't send response as that's done in the call every burst call above.
794
}
8✔
795

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

804
    PayloadHeader burst_packet{};
282✔
805
    burst_packet.req_opcode = Opcode::CMD_BURST_READ_FILE;
282✔
806
    burst_packet.seq_number = _burst_seq++;
282✔
807

808
    _make_burst_packet(burst_packet);
282✔
809

810
    _send_mavlink_ftp_message(burst_packet);
282✔
811

812
    if (burst_packet.burst_complete == 1) {
282✔
813
        return true;
8✔
814
    }
815

816
    return false;
274✔
817
}
282✔
818

819
void MavlinkFtpServer::_make_burst_packet(PayloadHeader& packet)
282✔
820
{
821
    uint32_t bytes_to_read = std::min(
282✔
822
        static_cast<uint32_t>(_session_info.burst_chunk_size),
282✔
823
        _session_info.file_size - _session_info.burst_offset);
564✔
824

825
    if (_debugging) {
282✔
826
        LogDebug() << "Burst read of " << bytes_to_read << " bytes";
×
827
    }
828
    _session_info.ifstream.read(reinterpret_cast<char*>(packet.data), bytes_to_read);
282✔
829

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

838
    const uint32_t bytes_read = _session_info.ifstream.gcount();
282✔
839
    packet.size = bytes_read;
282✔
840
    packet.opcode = Opcode::RSP_ACK;
282✔
841

842
    packet.offset = _session_info.burst_offset;
282✔
843
    _session_info.burst_offset += bytes_read;
282✔
844

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

854
void MavlinkFtpServer::_work_write(const PayloadHeader& payload)
95✔
855
{
856
    auto response = PayloadHeader{};
95✔
857
    response.seq_number = payload.seq_number + 1;
95✔
858
    response.req_opcode = payload.opcode;
95✔
859

860
    std::lock_guard<std::mutex> lock(_mutex);
95✔
861
    if (payload.session != 0 && !_session_info.ofstream.is_open()) {
95✔
862
        _reset();
×
863
    }
864

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

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

885
    response.opcode = Opcode::RSP_ACK;
95✔
886
    response.size = 0;
95✔
887

888
    _send_mavlink_ftp_message(response);
95✔
889
}
95✔
890

891
void MavlinkFtpServer::_work_terminate(const PayloadHeader& payload)
31✔
892
{
893
    {
894
        std::lock_guard<std::mutex> lock(_mutex);
31✔
895
        _reset();
31✔
896
    }
31✔
897

898
    auto response = PayloadHeader{};
31✔
899
    response.seq_number = payload.seq_number + 1;
31✔
900
    response.req_opcode = payload.opcode;
31✔
901
    response.opcode = Opcode::RSP_ACK;
31✔
902
    response.size = 0;
31✔
903
    _send_mavlink_ftp_message(response);
31✔
904
}
31✔
905

906
void MavlinkFtpServer::_reset()
106✔
907
{
908
    // requires lock
909
    if (_session_info.ifstream.is_open()) {
106✔
910
        _session_info.ifstream.close();
13✔
911
    }
912

913
    if (_session_info.ofstream.is_open()) {
106✔
914
        _session_info.ofstream.close();
5✔
915
    }
916

917
    _session_info.burst_stop = true;
106✔
918
    if (_session_info.burst_thread.joinable()) {
106✔
919
        _session_info.burst_thread.join();
8✔
920
    }
921
}
106✔
922

923
void MavlinkFtpServer::_work_reset(const PayloadHeader& payload)
×
924
{
925
    {
926
        std::lock_guard<std::mutex> lock(_mutex);
×
927
        _reset();
×
928
    }
×
929

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

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

944
    std::lock_guard<std::mutex> lock(_mutex);
2✔
945

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

955
    fs::path path = std::get<std::string>(maybe_path);
2✔
956

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

974
    _send_mavlink_ftp_message(response);
2✔
975
}
2✔
976

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

983
    std::lock_guard<std::mutex> lock(_mutex);
3✔
984

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

994
    auto path = std::get<std::string>(maybe_path);
1✔
995

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

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

1014
    _send_mavlink_ftp_message(response);
1✔
1015
}
5✔
1016

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

1023
    std::lock_guard<std::mutex> lock(_mutex);
4✔
1024

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

1034
    auto path = std::get<std::string>(maybe_path);
2✔
1035

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

1052
    _send_mavlink_ftp_message(response);
1✔
1053
}
8✔
1054

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

1061
    std::lock_guard<std::mutex> lock(_mutex);
2✔
1062

1063
    auto maybe_old_name = _path_from_payload(payload, 0);
2✔
1064

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

1073
    auto old_name = std::get<std::string>(maybe_old_name);
1✔
1074

1075
    auto maybe_new_name = _path_from_payload(payload, 1);
1✔
1076

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

1085
    auto new_name = std::get<std::string>(maybe_new_name);
1✔
1086

1087
    if (_debugging) {
1✔
1088
        LogDebug() << "Rename from old_name " << old_name << " to " << new_name;
×
1089
    }
1090

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

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

1109
    _send_mavlink_ftp_message(response);
1✔
1110
}
3✔
1111

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

1120
    std::ifstream ifstream;
2✔
1121
    ifstream.open(path, std::ios::in | std::ios::binary);
2✔
1122

1123
    if (!ifstream.is_open()) {
2✔
1124
        return ServerResult::ERR_FILE_IO_ERROR;
×
1125
    }
1126

1127
    // Read whole file in buffer size chunks
1128
    Crc32 checksum;
2✔
1129
    char buffer[18392];
2✔
1130
    do {
1131
        ifstream.read(buffer, sizeof(buffer));
2✔
1132

1133
        if (ifstream.fail() && !ifstream.eof()) {
2✔
1134
            ifstream.close();
×
1135
            return ServerResult::ERR_FILE_IO_ERROR;
×
1136
        }
1137

1138
        auto bytes_read = ifstream.gcount();
2✔
1139
        checksum.add((uint8_t*)buffer, bytes_read);
2✔
1140

1141
    } while (!ifstream.eof());
2✔
1142

1143
    ifstream.close();
2✔
1144

1145
    csum = checksum.get();
2✔
1146

1147
    return ServerResult::SUCCESS;
2✔
1148
}
2✔
1149

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

1156
    std::lock_guard<std::mutex> lock(_mutex);
3✔
1157

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

1167
    auto path = std::get<std::string>(maybe_path);
2✔
1168

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

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

1188
    response.opcode = Opcode::RSP_ACK;
2✔
1189
    response.size = sizeof(uint32_t);
2✔
1190
    std::memcpy(response.data, &checksum, response.size);
2✔
1191

1192
    _send_mavlink_ftp_message(response);
2✔
1193
}
4✔
1194

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

© 2025 Coveralls, Inc