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

mavlink / MAVSDK / 4899817366

pending completion
4899817366

Pull #1772

github

GitHub
Merge c0bb90862 into e4e9c71dd
Pull Request #1772: Refactor MAVLinkParameters into client and server classes

2192 of 2192 new or added lines in 34 files covered. (100.0%)

7708 of 24812 relevant lines covered (31.07%)

19.96 hits per line

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

40.71
/src/mavsdk/core/system_impl.cpp
1
#include "system.h"
2
#include "mavsdk_impl.h"
3
#include "mavlink_include.h"
4
#include "system_impl.h"
5
#include "plugin_impl_base.h"
6
#include "px4_custom_mode.h"
7
#include "ardupilot_custom_mode.h"
8
#include "request_message.h"
9
#include "callback_list.tpp"
10
#include "unused.h"
11
#include <cassert>
12
#include <cstdlib>
13
#include <functional>
14
#include <future>
15
#include <utility>
16

17
namespace mavsdk {
18

19
template class CallbackList<bool>;
20
template class CallbackList<System::ComponentType>;
21
template class CallbackList<System::ComponentType, uint8_t>;
22

23
SystemImpl::SystemImpl(MavsdkImpl& parent) :
20✔
24
    Sender(),
25
    _mavsdk_impl(parent),
26
    _command_sender(*this),
27
    _timesync(*this),
28
    _ping(*this),
29
    _mission_transfer(
30
        *this,
31
        _mavsdk_impl.mavlink_message_handler,
20✔
32
        _mavsdk_impl.timeout_handler,
20✔
33
        [this]() { return timeout_s(); }),
1✔
34
    _request_message(
35
        *this, _command_sender, _mavsdk_impl.mavlink_message_handler, _mavsdk_impl.timeout_handler),
20✔
36
    _mavlink_ftp(*this)
20✔
37
{
38
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
20✔
39
}
20✔
40

41
SystemImpl::~SystemImpl()
20✔
42
{
43
    _should_exit = true;
20✔
44
    _mavsdk_impl.mavlink_message_handler.unregister_all(this);
20✔
45

46
    if (!_always_connected) {
20✔
47
        unregister_timeout_handler(_heartbeat_timeout_cookie);
10✔
48
    }
49

50
    if (_system_thread != nullptr) {
20✔
51
        _system_thread->join();
20✔
52
        delete _system_thread;
20✔
53
        _system_thread = nullptr;
20✔
54
    }
55
}
20✔
56

57
void SystemImpl::init(uint8_t system_id, uint8_t comp_id, bool connected)
20✔
58
{
59
    _target_address.system_id = system_id;
20✔
60
    // We use this as a default.
61
    _target_address.component_id = MAV_COMP_ID_AUTOPILOT1;
20✔
62

63
    if (connected) {
20✔
64
        _always_connected = true;
10✔
65
        set_connected();
10✔
66
    }
67

68
    _mavsdk_impl.mavlink_message_handler.register_one(
20✔
69
        MAVLINK_MSG_ID_HEARTBEAT,
70
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
20✔
71
        this);
72

73
    _mavsdk_impl.mavlink_message_handler.register_one(
20✔
74
        MAVLINK_MSG_ID_STATUSTEXT,
75
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
76
        this);
77

78
    _mavsdk_impl.mavlink_message_handler.register_one(
20✔
79
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
80
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
12✔
81
        this);
82

83
    // register_mavlink_command_handler(
84
    //    MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
85
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
86
    //        return process_autopilot_version_request(command);
87
    //    },
88
    //    this);
89

90
    //// TO-DO!
91
    // register_mavlink_command_handler(
92
    //    MAV_CMD_REQUEST_MESSAGE,
93
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
94
    //        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
95
    //    },
96
    //    this);
97

98
    add_new_component(comp_id);
20✔
99
}
20✔
100

101
bool SystemImpl::is_connected() const
19✔
102
{
103
    return _connected;
19✔
104
}
105

106
void SystemImpl::register_mavlink_message_handler(
89✔
107
    uint16_t msg_id, const MavlinkMessageHandler& callback, const void* cookie)
108
{
109
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, callback, cookie);
89✔
110
}
89✔
111

112
void SystemImpl::register_mavlink_message_handler(
7✔
113
    uint16_t msg_id, uint8_t cmp_id, const MavlinkMessageHandler& callback, const void* cookie)
114
{
115
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, cmp_id, callback, cookie);
7✔
116
}
7✔
117

118
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
119
{
120
    _mavsdk_impl.mavlink_message_handler.unregister_one(msg_id, cookie);
×
121
}
×
122

123
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
64✔
124
{
125
    _mavsdk_impl.mavlink_message_handler.unregister_all(cookie);
64✔
126
}
64✔
127

128
void SystemImpl::update_componentid_messages_handler(
×
129
    uint16_t msg_id, uint8_t cmp_id, const void* cookie)
130
{
131
    _mavsdk_impl.mavlink_message_handler.update_component_id(msg_id, cmp_id, cookie);
×
132
}
×
133

134
void SystemImpl::register_timeout_handler(
27✔
135
    const std::function<void()>& callback, double duration_s, void** cookie)
136
{
137
    _mavsdk_impl.timeout_handler.add(callback, duration_s, cookie);
27✔
138
}
27✔
139

140
void SystemImpl::refresh_timeout_handler(const void* cookie)
1✔
141
{
142
    _mavsdk_impl.timeout_handler.refresh(cookie);
1✔
143
}
1✔
144

145
void SystemImpl::unregister_timeout_handler(const void* cookie)
24✔
146
{
147
    _mavsdk_impl.timeout_handler.remove(cookie);
24✔
148
}
24✔
149

150
double SystemImpl::timeout_s() const
56✔
151
{
152
    return _mavsdk_impl.timeout_s();
56✔
153
}
154

155
void SystemImpl::enable_timesync()
×
156
{
157
    _timesync.enable();
×
158
}
×
159

160
System::IsConnectedHandle
161
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
162
{
163
    std::lock_guard<std::mutex> lock(_connection_mutex);
×
164
    return _is_connected_callbacks.subscribe(callback);
×
165
}
166

167
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
168
{
169
    _is_connected_callbacks.unsubscribe(handle);
×
170
}
×
171

172
void SystemImpl::add_call_every(std::function<void()> callback, float interval_s, void** cookie)
4✔
173
{
174
    _mavsdk_impl.call_every_handler.add(
8✔
175
        std::move(callback), static_cast<double>(interval_s), cookie);
4✔
176
}
4✔
177

178
void SystemImpl::change_call_every(float interval_s, const void* cookie)
×
179
{
180
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
181
}
×
182

183
void SystemImpl::reset_call_every(const void* cookie)
×
184
{
185
    _mavsdk_impl.call_every_handler.reset(cookie);
×
186
}
×
187

188
void SystemImpl::remove_call_every(const void* cookie)
10✔
189
{
190
    _mavsdk_impl.call_every_handler.remove(cookie);
10✔
191
}
10✔
192

193
void SystemImpl::register_statustext_handler(
1✔
194
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
195
{
196
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
197
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
1✔
198
}
1✔
199

200
void SystemImpl::unregister_statustext_handler(void* cookie)
1✔
201
{
202
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
203
    _statustext_handler_callbacks.erase(std::remove_if(
1✔
204
        _statustext_handler_callbacks.begin(),
205
        _statustext_handler_callbacks.end(),
206
        [&](const auto& entry) { return entry.cookie == cookie; }));
2✔
207
}
1✔
208

209
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
20✔
210
{
211
    mavlink_heartbeat_t heartbeat;
20✔
212
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
20✔
213

214
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
20✔
215
        _autopilot = Autopilot::Px4;
×
216
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
20✔
217
        _autopilot = Autopilot::ArduPilot;
×
218
    }
219

220
    // Only set the vehicle type if the heartbeat is from an autopilot component
221
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
222
    // last enumerator.
223
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
20✔
224
        LogErr() << "type received in HEARTBEAT was not recognized";
×
225
    } else {
226
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
20✔
227
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
20✔
228
            new_vehicle_type != MAV_TYPE_GENERIC) {
229
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
×
230
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
×
231
            _vehicle_type = new_vehicle_type;
×
232
        }
233
    }
234

235
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
20✔
236
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
10✔
237
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
10✔
238
    }
239
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
20✔
240
        _flight_mode =
×
241
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
242
    }
243

244
    set_connected();
20✔
245
}
20✔
246

247
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
248
{
249
    mavlink_statustext_t statustext;
3✔
250
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
251

252
    const auto maybe_result = _statustext_handler.process(statustext);
6✔
253

254
    if (maybe_result.has_value()) {
3✔
255
        LogDebug() << "MAVLink: "
6✔
256
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
257
                   << maybe_result.value().text;
9✔
258

259
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
6✔
260
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
261
            entry.callback(maybe_result.value());
3✔
262
        }
263
    }
264
}
3✔
265

266
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
12✔
267
{
268
    mavlink_autopilot_version_t autopilot_version;
12✔
269
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
12✔
270

271
    _mission_transfer.set_int_messages_supported(
12✔
272
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
12✔
273
}
12✔
274

275
void SystemImpl::heartbeats_timed_out()
×
276
{
277
    LogInfo() << "heartbeats timed out";
×
278
    set_disconnected();
×
279
}
×
280

281
void SystemImpl::system_thread()
20✔
282
{
283
    SteadyTimePoint last_ping_time{};
20✔
284

285
    while (!_should_exit) {
629✔
286
        {
287
            std::lock_guard<std::mutex> lock(_mavlink_parameter_senders_mutex);
1,218✔
288
            for (auto& entry : _mavlink_parameter_senders) {
896✔
289
                entry.parameter_sender->do_work();
287✔
290
            }
291
        }
292
        _command_sender.do_work();
609✔
293
        _timesync.do_work();
609✔
294
        _mission_transfer.do_work();
609✔
295

296
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
609✔
297
            if (_connected) {
20✔
298
                _ping.run_once();
10✔
299
            }
300
            last_ping_time = _mavsdk_impl.time.steady_time();
20✔
301
        }
302

303
        if (_connected) {
609✔
304
            // Work fairly fast if we're connected.
305
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
599✔
306
        } else {
307
            // Be less aggressive when unconnected.
308
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
10✔
309
        }
310
    }
311
}
20✔
312

313
// std::optional<mavlink_message_t>
314
// SystemImpl::process_autopilot_version_request(const MavlinkCommandReceiver::CommandLong& command)
315
//{
316
//    if (_should_send_autopilot_version) {
317
//        send_autopilot_version();
318
//        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
319
//    }
320
//
321
//    return {};
322
//}
323

324
std::string SystemImpl::component_name(uint8_t component_id)
20✔
325
{
326
    switch (component_id) {
20✔
327
        case MAV_COMP_ID_AUTOPILOT1:
9✔
328
            return "Autopilot";
9✔
329
        case MAV_COMP_ID_CAMERA:
1✔
330
            return "Camera 1";
1✔
331
        case MAV_COMP_ID_CAMERA2:
×
332
            return "Camera 2";
×
333
        case MAV_COMP_ID_CAMERA3:
×
334
            return "Camera 3";
×
335
        case MAV_COMP_ID_CAMERA4:
×
336
            return "Camera 4";
×
337
        case MAV_COMP_ID_CAMERA5:
×
338
            return "Camera 5";
×
339
        case MAV_COMP_ID_CAMERA6:
×
340
            return "Camera 6";
×
341
        case MAV_COMP_ID_GIMBAL:
×
342
            return "Gimbal";
×
343
        case MAV_COMP_ID_MISSIONPLANNER:
10✔
344
            return "Ground station";
10✔
345
        case MAV_COMP_ID_WINCH:
×
346
            return "Winch";
×
347
        default:
×
348
            return "Unsupported component";
×
349
    }
350
}
351

352
System::ComponentType SystemImpl::component_type(uint8_t component_id)
40✔
353
{
354
    switch (component_id) {
40✔
355
        case MAV_COMP_ID_AUTOPILOT1:
18✔
356
            return System::ComponentType::AUTOPILOT;
18✔
357
        case MAV_COMP_ID_CAMERA:
2✔
358
        case MAV_COMP_ID_CAMERA2:
359
        case MAV_COMP_ID_CAMERA3:
360
        case MAV_COMP_ID_CAMERA4:
361
        case MAV_COMP_ID_CAMERA5:
362
        case MAV_COMP_ID_CAMERA6:
363
            return System::ComponentType::CAMERA;
2✔
364
        case MAV_COMP_ID_GIMBAL:
×
365
            return System::ComponentType::GIMBAL;
×
366
        default:
20✔
367
            return System::ComponentType::UNKNOWN;
20✔
368
    }
369
}
370

371
void SystemImpl::add_new_component(uint8_t component_id)
200✔
372
{
373
    if (component_id == 0) {
200✔
374
        return;
10✔
375
    }
376

377
    auto res_pair = _components.insert(component_id);
190✔
378
    if (res_pair.second) {
190✔
379
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
40✔
380
        _component_discovered_callbacks.queue(
20✔
381
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
382
        _component_discovered_id_callbacks.queue(
20✔
383
            component_type(component_id), component_id, [this](const auto& func) {
×
384
                call_user_callback(func);
×
385
            });
×
386
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
80✔
387
                   << ") added.";
80✔
388
    }
389
}
390

391
size_t SystemImpl::total_components() const
×
392
{
393
    return _components.size();
×
394
}
395

396
System::ComponentDiscoveredHandle
397
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
398
{
399
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
400
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
401

402
    if (total_components() > 0) {
×
403
        for (const auto& elem : _components) {
×
404
            _component_discovered_callbacks.queue(
×
405
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
406
        }
407
    }
408
    return handle;
×
409
}
410

411
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
412
{
413
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
414
    _component_discovered_callbacks.unsubscribe(handle);
×
415
}
×
416

417
System::ComponentDiscoveredIdHandle
418
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
419
{
420
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
421
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
422

423
    if (total_components() > 0) {
×
424
        for (const auto& elem : _components) {
×
425
            _component_discovered_id_callbacks.queue(
×
426
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
427
        }
428
    }
429
    return handle;
×
430
}
431

432
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
433
{
434
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
435
    _component_discovered_id_callbacks.unsubscribe(handle);
×
436
}
×
437

438
bool SystemImpl::is_standalone() const
×
439
{
440
    return !has_autopilot();
×
441
}
442

443
bool SystemImpl::has_autopilot() const
39✔
444
{
445
    return get_autopilot_id() != uint8_t(0);
39✔
446
}
447

448
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
449
{
450
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
451
}
452

453
bool SystemImpl::is_camera(uint8_t comp_id)
1✔
454
{
455
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
1✔
456
}
457

458
bool SystemImpl::has_camera(int camera_id) const
1✔
459
{
460
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
1✔
461

462
    if (camera_comp_id == -1) { // Check whether the system has any camera.
1✔
463
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
1✔
464
            return true;
1✔
465
        }
466
    } else { // Look for the camera whose id is `camera_id`.
467
        for (auto compid : _components) {
×
468
            if (compid == camera_comp_id) {
×
469
                return true;
×
470
            }
471
        }
472
    }
473
    return false;
×
474
}
475

476
bool SystemImpl::has_gimbal() const
×
477
{
478
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
479
}
480

481
bool SystemImpl::send_message(mavlink_message_t& message)
80✔
482
{
483
    return _mavsdk_impl.send_message(message);
80✔
484
}
485

486
void SystemImpl::send_autopilot_version_request()
×
487
{
488
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
489
    auto fut = prom.get_future();
×
490

491
    send_autopilot_version_request_async(
×
492
        [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
493

494
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
495
        _old_message_520_supported = false;
×
496
        LogWarn() << "Trying alternative command (512).";
×
497
        send_autopilot_version_request();
×
498
    }
499
}
×
500

501
void SystemImpl::send_autopilot_version_request_async(
9✔
502
    const MavlinkCommandSender::CommandResultCallback& callback)
503
{
504
    MavlinkCommandSender::CommandLong command{};
9✔
505
    command.target_component_id = get_autopilot_id();
9✔
506

507
    if (_old_message_520_supported) {
9✔
508
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
509
        // release.
510
        command.command = MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES;
9✔
511
        command.params.maybe_param1 = 1.0f;
9✔
512
    } else {
513
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
514
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_AUTOPILOT_VERSION)};
×
515
    }
516

517
    send_command_async(command, callback);
9✔
518
}
9✔
519

520
void SystemImpl::send_flight_information_request()
×
521
{
522
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
523
    auto fut = prom.get_future();
×
524

525
    MavlinkCommandSender::CommandLong command{};
×
526
    command.target_component_id = get_autopilot_id();
×
527

528
    if (_old_message_528_supported) {
×
529
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
530
        // release.
531
        command.command = MAV_CMD_REQUEST_FLIGHT_INFORMATION;
×
532
        command.params.maybe_param1 = 1.0f;
×
533
    } else {
534
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
535
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_FLIGHT_INFORMATION)};
×
536
    }
537

538
    send_command_async(
×
539
        command, [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
540
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
541
        _old_message_528_supported = false;
×
542
        LogWarn() << "Trying alternative command (512)..";
×
543
        send_flight_information_request();
×
544
    }
545
}
×
546

547
void SystemImpl::set_connected()
30✔
548
{
549
    bool enable_needed = false;
30✔
550
    {
551
        std::lock_guard<std::mutex> lock(_connection_mutex);
60✔
552

553
        if (!_connected) {
30✔
554
            if (!_components.empty()) {
20✔
555
                LogDebug() << "Discovered " << _components.size() << " component(s)";
10✔
556
            }
557

558
            _connected = true;
20✔
559

560
            // System with sysid 0 is a bit special: it is a placeholder for a connection initiated
561
            // by MAVSDK. As such, it should not be advertised as a newly discovered system.
562
            if (static_cast<int>(get_system_id()) != 0) {
20✔
563
                _mavsdk_impl.notify_on_discover();
10✔
564
            }
565

566
            // We call this later to avoid deadlocks on creating the server components.
567
            _mavsdk_impl.call_user_callback([this]() {
40✔
568
                // Send a heartbeat back immediately.
569
                _mavsdk_impl.start_sending_heartbeats();
570
            });
571

572
            if (!_always_connected) {
20✔
573
                register_timeout_handler(
10✔
574
                    [this] { heartbeats_timed_out(); },
×
575
                    HEARTBEAT_TIMEOUT_S,
576
                    &_heartbeat_timeout_cookie);
577
            }
578
            enable_needed = true;
20✔
579

580
            _is_connected_callbacks.queue(
20✔
581
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
582

583
        } else if (_connected && !_always_connected) {
10✔
584
            refresh_timeout_handler(_heartbeat_timeout_cookie);
1✔
585
        }
586
        // If not yet connected there is nothing to do/
587
    }
588
    if (enable_needed) {
30✔
589
        if (has_autopilot()) {
20✔
590
            send_autopilot_version_request_async(nullptr);
9✔
591
        }
592

593
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
40✔
594
        for (auto plugin_impl : _plugin_impls) {
20✔
595
            plugin_impl->enable();
×
596
        }
597
    }
598
}
30✔
599

600
void SystemImpl::set_disconnected()
×
601
{
602
    {
603
        std::lock_guard<std::mutex> lock(_connection_mutex);
×
604

605
        // This might not be needed because this is probably called from the triggered
606
        // timeout anyway, but it should also do no harm.
607
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
608
        //_heartbeat_timeout_cookie = nullptr;
609

610
        _connected = false;
×
611
        _mavsdk_impl.notify_on_timeout();
×
612
        _is_connected_callbacks.queue(
×
613
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
614
    }
615

616
    _mavsdk_impl.stop_sending_heartbeats();
×
617

618
    {
619
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
620
        for (auto plugin_impl : _plugin_impls) {
×
621
            plugin_impl->disable();
×
622
        }
623
    }
624
}
×
625

626
uint8_t SystemImpl::get_system_id() const
82✔
627
{
628
    return _target_address.system_id;
82✔
629
}
630

631
std::vector<uint8_t> SystemImpl::component_ids() const
×
632
{
633
    return std::vector<uint8_t>{_components.begin(), _components.end()};
×
634
}
635

636
void SystemImpl::set_system_id(uint8_t system_id)
10✔
637
{
638
    _target_address.system_id = system_id;
10✔
639
}
10✔
640

641
uint8_t SystemImpl::get_own_system_id() const
94✔
642
{
643
    return _mavsdk_impl.get_own_system_id();
94✔
644
}
645

646
uint8_t SystemImpl::get_own_component_id() const
94✔
647
{
648
    return _mavsdk_impl.get_own_component_id();
94✔
649
}
650

651
MAV_TYPE SystemImpl::get_vehicle_type() const
×
652
{
653
    return _vehicle_type;
×
654
}
655

656
uint8_t SystemImpl::get_own_mav_type() const
×
657
{
658
    return _mavsdk_impl.get_mav_type();
×
659
}
660

661
MavlinkParameterSender::Result SystemImpl::set_param(
×
662
    const std::string& name,
663
    ParamValue value,
664
    std::optional<uint8_t> maybe_component_id,
665
    bool extended)
666
{
667
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
668
        ->set_param(name, value);
×
669
}
670

671
MavlinkParameterSender::Result SystemImpl::set_param_float(
2✔
672
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
673
{
674
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
675
        ->set_param_float(name, value);
4✔
676
}
677

678
MavlinkParameterSender::Result SystemImpl::set_param_int(
2✔
679
    const std::string& name,
680
    int32_t value,
681
    std::optional<uint8_t> maybe_component_id,
682
    bool extended)
683
{
684
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
685
        ->set_param_int(name, value);
4✔
686
}
687

688
MavlinkParameterSender::Result SystemImpl::set_param_custom(
2✔
689
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
690
{
691
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
692
        ->set_param_custom(name, value);
4✔
693
}
694

695
std::pair<MavlinkParameterSender::Result, std::map<std::string, ParamValue>>
696
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
697
{
698
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
699
        ->get_all_params();
8✔
700
}
701

702
void SystemImpl::set_param_async(
×
703
    const std::string& name,
704
    ParamValue value,
705
    const SetParamCallback& callback,
706
    const void* cookie,
707
    std::optional<uint8_t> maybe_component_id,
708
    bool extended)
709
{
710
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
711
        ->set_param_async(name, value, callback, cookie);
×
712
}
×
713

714
void SystemImpl::set_param_float_async(
×
715
    const std::string& name,
716
    float value,
717
    const SetParamCallback& callback,
718
    const void* cookie,
719
    std::optional<uint8_t> maybe_component_id,
720
    bool extended)
721
{
722
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
723
        ->set_param_float_async(name, value, callback, cookie);
×
724
}
×
725

726
void SystemImpl::set_param_int_async(
×
727
    const std::string& name,
728
    int32_t value,
729
    const SetParamCallback& callback,
730
    const void* cookie,
731
    std::optional<uint8_t> maybe_component_id,
732
    bool extended)
733
{
734
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
735
        ->set_param_int_async(name, value, callback, cookie);
×
736
}
×
737

738
std::pair<MavlinkParameterSender::Result, float> SystemImpl::get_param_float(
5✔
739
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
740
{
741
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
742
        ->get_param_float(name);
10✔
743
}
744

745
std::pair<MavlinkParameterSender::Result, int> SystemImpl::get_param_int(
5✔
746
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
747
{
748
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
749
        ->get_param_int(name);
10✔
750
}
751

752
std::pair<MavlinkParameterSender::Result, std::string>
753
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
754
{
755
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
756
        ->get_param_custom(name);
8✔
757
}
758

759
void SystemImpl::get_param_async(
×
760
    const std::string& name,
761
    ParamValue value,
762
    const GetParamAnyCallback& callback,
763
    const void* cookie,
764
    std::optional<uint8_t> maybe_component_id,
765
    bool extended)
766
{
767
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
768
        ->get_param_async(name, value, callback, cookie);
×
769
}
×
770

771
void SystemImpl::get_param_float_async(
×
772
    const std::string& name,
773
    const GetParamFloatCallback& callback,
774
    const void* cookie,
775
    std::optional<uint8_t> maybe_component_id,
776
    bool extended)
777
{
778
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
779
        ->get_param_float_async(name, callback, cookie);
×
780
}
×
781

782
void SystemImpl::get_param_int_async(
×
783
    const std::string& name,
784
    const GetParamIntCallback& callback,
785
    const void* cookie,
786
    std::optional<uint8_t> maybe_component_id,
787
    bool extended)
788
{
789
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
790
        ->get_param_int_async(name, callback, cookie);
×
791
}
×
792

793
void SystemImpl::get_param_custom_async(
×
794
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
795
{
796
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
797
}
×
798

799
void SystemImpl::cancel_all_param(const void* cookie)
2✔
800
{
801
    UNUSED(cookie);
2✔
802
    // FIXME: this currently crashes on destruction
803
    // param_sender(1, false)->cancel_all_param(cookie);
804
}
2✔
805

806
MavlinkCommandSender::Result
807
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
808
{
809
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
810
        make_command_flight_mode(system_mode, component_id);
×
811

812
    if (result.first != MavlinkCommandSender::Result::Success) {
×
813
        return result.first;
×
814
    }
815

816
    return send_command(result.second);
×
817
}
818

819
void SystemImpl::set_flight_mode_async(
×
820
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
821
{
822
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
823
        make_command_flight_mode(system_mode, component_id);
×
824

825
    if (result.first != MavlinkCommandSender::Result::Success) {
×
826
        if (callback) {
×
827
            callback(result.first, NAN);
×
828
        }
829
        return;
×
830
    }
831

832
    send_command_async(result.second, callback);
×
833
}
834

835
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
836
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
837
{
838
    if (_autopilot == Autopilot::ArduPilot) {
×
839
        return make_command_ardupilot_mode(flight_mode, component_id);
×
840
    } else {
841
        return make_command_px4_mode(flight_mode, component_id);
×
842
    }
843
}
844

845
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
846
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
847
{
848
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
849
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
850
    const uint8_t mode_type =
×
851
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
852

853
    MavlinkCommandSender::CommandLong command{};
×
854

855
    command.command = MAV_CMD_DO_SET_MODE;
×
856
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
857

858
    switch (_vehicle_type) {
×
859
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
860
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER:
861
            if (flight_mode_to_ardupilot_rover_mode(flight_mode) == ardupilot::RoverMode::Unknown) {
×
862
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
863
                MavlinkCommandSender::CommandLong empty_command{};
×
864
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
865
            } else {
866
                command.params.maybe_param2 =
×
867
                    static_cast<float>(flight_mode_to_ardupilot_rover_mode(flight_mode));
×
868
            }
869
            break;
×
870
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
871
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
872
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
873
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
874
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
875
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
876
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
877
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
878
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
879
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
880
                MavlinkCommandSender::CommandLong empty_command{};
×
881
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
882
            } else {
883
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
884
            }
885
            break;
×
886
        }
887

888
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
889
        case MAV_TYPE::MAV_TYPE_COAXIAL:
890
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
891
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
892
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
893
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
894
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
895
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
896
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
897
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
898
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
899
                MavlinkCommandSender::CommandLong empty_command{};
×
900
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
901
            } else {
902
                command.params.maybe_param2 =
×
903
                    static_cast<float>(flight_mode_to_ardupilot_copter_mode(flight_mode));
×
904
            }
905
            break;
×
906
        }
907

908
        default:
×
909
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
910
                     << _vehicle_type;
×
911
            MavlinkCommandSender::CommandLong empty_command{};
×
912
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
913
    }
914
    command.target_component_id = component_id;
×
915

916
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
917
}
918
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
919
{
920
    switch (flight_mode) {
×
921
        case FlightMode::Mission:
×
922
            return ardupilot::RoverMode::Auto;
×
923
        case FlightMode::Acro:
×
924
            return ardupilot::RoverMode::Acro;
×
925
        case FlightMode::Hold:
×
926
            return ardupilot::RoverMode::Hold;
×
927
        case FlightMode::ReturnToLaunch:
×
928
            return ardupilot::RoverMode::RTL;
×
929
        case FlightMode::Manual:
×
930
            return ardupilot::RoverMode::Manual;
×
931
        case FlightMode::FollowMe:
×
932
            return ardupilot::RoverMode::Follow;
×
933
        case FlightMode::Offboard:
×
934
            return ardupilot::RoverMode::Guided;
×
935
        case FlightMode::Unknown:
×
936
        case FlightMode::Ready:
937
        case FlightMode::Takeoff:
938
        case FlightMode::Land:
939
        case FlightMode::Altctl:
940
        case FlightMode::Posctl:
941
        case FlightMode::Rattitude:
942
        case FlightMode::Stabilized:
943
        default:
944
            return ardupilot::RoverMode::Unknown;
×
945
    }
946
}
947
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
948
{
949
    switch (flight_mode) {
×
950
        case FlightMode::Mission:
×
951
            return ardupilot::CopterMode::Auto;
×
952
        case FlightMode::Acro:
×
953
            return ardupilot::CopterMode::Acro;
×
954
        case FlightMode::Hold:
×
955
            return ardupilot::CopterMode::Loiter;
×
956
        case FlightMode::ReturnToLaunch:
×
957
            return ardupilot::CopterMode::Rtl;
×
958
        case FlightMode::Land:
×
959
            return ardupilot::CopterMode::Land;
×
960
        case FlightMode::Manual:
×
961
            return ardupilot::CopterMode::Stabilize;
×
962
        case FlightMode::FollowMe:
×
963
            return ardupilot::CopterMode::Follow;
×
964
        case FlightMode::Offboard:
×
965
            return ardupilot::CopterMode::Guided;
×
966
        case FlightMode::Altctl:
×
967
            return ardupilot::CopterMode::AltHold;
×
968
        case FlightMode::Posctl:
×
969
            return ardupilot::CopterMode::PosHold;
×
970
        case FlightMode::Stabilized:
×
971
            return ardupilot::CopterMode::Stabilize;
×
972
        case FlightMode::Unknown:
×
973
        case FlightMode::Ready:
974
        case FlightMode::Takeoff:
975
        case FlightMode::Rattitude:
976
        default:
977
            return ardupilot::CopterMode::Unknown;
×
978
    }
979
}
980
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
981
{
982
    switch (flight_mode) {
×
983
        case FlightMode::Mission:
×
984
            return ardupilot::PlaneMode::Auto;
×
985
        case FlightMode::Acro:
×
986
            return ardupilot::PlaneMode::Acro;
×
987
        case FlightMode::Hold:
×
988
            return ardupilot::PlaneMode::Loiter;
×
989
        case FlightMode::ReturnToLaunch:
×
990
            return ardupilot::PlaneMode::Rtl;
×
991
        case FlightMode::Manual:
×
992
            return ardupilot::PlaneMode::Manual;
×
993
        case FlightMode::FBWA:
×
994
            return ardupilot::PlaneMode::Fbwa;
×
995
        case FlightMode::Stabilized:
×
996
            return ardupilot::PlaneMode::Stabilize;
×
997
        case FlightMode::Unknown:
×
998
            return ardupilot::PlaneMode::Unknown;
×
999
        default:
×
1000
            return ardupilot::PlaneMode::Unknown;
×
1001
    }
1002
}
1003

1004
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1005
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1006
{
1007
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1008
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1009

1010
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1011

1012
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1013
    //       but want to be rather safe than sorry.
1014
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1015
    uint8_t custom_sub_mode = 0;
×
1016

1017
    switch (flight_mode) {
×
1018
        case FlightMode::Hold:
×
1019
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1020
            break;
×
1021
        case FlightMode::ReturnToLaunch:
×
1022
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1023
            break;
×
1024
        case FlightMode::Takeoff:
×
1025
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1026
            break;
×
1027
        case FlightMode::Land:
×
1028
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1029
            break;
×
1030
        case FlightMode::Mission:
×
1031
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1032
            break;
×
1033
        case FlightMode::FollowMe:
×
1034
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1035
            break;
×
1036
        case FlightMode::Offboard:
×
1037
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1038
            break;
×
1039
        case FlightMode::Manual:
×
1040
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1041
            break;
×
1042
        case FlightMode::Posctl:
×
1043
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1044
            break;
×
1045
        case FlightMode::Altctl:
×
1046
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1047
            break;
×
1048
        case FlightMode::Rattitude:
×
1049
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1050
            break;
×
1051
        case FlightMode::Acro:
×
1052
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1053
            break;
×
1054
        case FlightMode::Stabilized:
×
1055
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1056
            break;
×
1057
        default:
×
1058
            LogErr() << "Unknown Flight mode.";
×
1059
            MavlinkCommandSender::CommandLong empty_command{};
×
1060
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1061
    }
1062

1063
    MavlinkCommandSender::CommandLong command{};
×
1064

1065
    command.command = MAV_CMD_DO_SET_MODE;
×
1066
    command.params.maybe_param1 = static_cast<float>(mode);
×
1067
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1068
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1069
    command.target_component_id = component_id;
×
1070

1071
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1072
}
1073

1074
FlightMode SystemImpl::get_flight_mode() const
6✔
1075
{
1076
    return _flight_mode;
6✔
1077
}
1078

1079
void SystemImpl::receive_float_param(
×
1080
    MavlinkParameterSender::Result result, ParamValue value, const GetParamFloatCallback& callback)
1081
{
1082
    if (callback) {
×
1083
        if (result == MavlinkParameterSender::Result::Success) {
×
1084
            callback(result, value.get<float>());
×
1085
        } else {
1086
            callback(result, NAN);
×
1087
        }
1088
    }
1089
}
×
1090

1091
void SystemImpl::receive_int_param(
×
1092
    MavlinkParameterSender::Result result, ParamValue value, const GetParamIntCallback& callback)
1093
{
1094
    if (callback) {
×
1095
        if (result == MavlinkParameterSender::Result::Success) {
×
1096
            callback(result, value.get<int32_t>());
×
1097
        } else {
1098
            callback(result, 0);
×
1099
        }
1100
    }
1101
}
×
1102

1103
uint8_t SystemImpl::get_autopilot_id() const
52✔
1104
{
1105
    for (auto compid : _components)
54✔
1106
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
42✔
1107
            return compid;
40✔
1108
        }
1109
    // FIXME: Not sure what should be returned if autopilot is not found
1110
    return uint8_t(0);
12✔
1111
}
1112

1113
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1114
{
1115
    std::vector<uint8_t> camera_ids{};
×
1116

1117
    for (auto compid : _components)
×
1118
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1119
            camera_ids.push_back(compid);
×
1120
        }
1121
    return camera_ids;
×
1122
}
1123

1124
uint8_t SystemImpl::get_gimbal_id() const
×
1125
{
1126
    for (auto compid : _components)
×
1127
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1128
            return compid;
×
1129
        }
1130
    return uint8_t(0);
×
1131
}
1132

1133
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
×
1134
{
1135
    if (_target_address.system_id == 0 && _components.empty()) {
×
1136
        return MavlinkCommandSender::Result::NoSystem;
×
1137
    }
1138
    command.target_system_id = get_system_id();
×
1139
    return _command_sender.send_command(command);
×
1140
}
1141

1142
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1143
{
1144
    if (_target_address.system_id == 0 && _components.empty()) {
×
1145
        return MavlinkCommandSender::Result::NoSystem;
×
1146
    }
1147
    command.target_system_id = get_system_id();
×
1148
    return _command_sender.send_command(command);
×
1149
}
1150

1151
void SystemImpl::send_command_async(
14✔
1152
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1153
{
1154
    if (_target_address.system_id == 0 && _components.empty()) {
14✔
1155
        if (callback) {
×
1156
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1157
        }
1158
        return;
×
1159
    }
1160
    command.target_system_id = get_system_id();
14✔
1161

1162
    _command_sender.queue_command_async(command, callback);
14✔
1163
}
1164

1165
void SystemImpl::send_command_async(
×
1166
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1167
{
1168
    if (_target_address.system_id == 0 && _components.empty()) {
×
1169
        if (callback) {
×
1170
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1171
        }
1172
        return;
×
1173
    }
1174
    command.target_system_id = get_system_id();
×
1175

1176
    _command_sender.queue_command_async(command, callback);
×
1177
}
1178

1179
MavlinkCommandSender::Result
1180
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1181
{
1182
    MavlinkCommandSender::CommandLong command =
×
1183
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1184
    return send_command(command);
×
1185
}
1186

1187
void SystemImpl::set_msg_rate_async(
1✔
1188
    uint16_t message_id,
1189
    double rate_hz,
1190
    const CommandResultCallback& callback,
1191
    uint8_t component_id)
1192
{
1193
    MavlinkCommandSender::CommandLong command =
1✔
1194
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1195
    send_command_async(command, callback);
1✔
1196
}
1✔
1197

1198
MavlinkCommandSender::CommandLong
1199
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1200
{
1201
    MavlinkCommandSender::CommandLong command{};
1✔
1202

1203
    // 0 to request default rate, -1 to stop stream
1204

1205
    float interval_us = 0.0f;
1✔
1206

1207
    if (rate_hz > 0) {
1✔
1208
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1209
    } else if (rate_hz < 0) {
×
1210
        interval_us = -1.0f;
×
1211
    }
1212

1213
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1214
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1215
    command.params.maybe_param2 = interval_us;
1✔
1216
    command.target_component_id = component_id;
1✔
1217

1218
    return command;
1✔
1219
}
1220

1221
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
12✔
1222
{
1223
    assert(plugin_impl);
12✔
1224

1225
    plugin_impl->init();
12✔
1226

1227
    {
1228
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
24✔
1229
        _plugin_impls.push_back(plugin_impl);
12✔
1230
    }
1231

1232
    // If we're connected already, let's enable it straightaway.
1233
    if (_connected) {
12✔
1234
        plugin_impl->enable();
12✔
1235
    }
1236
}
12✔
1237

1238
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
12✔
1239
{
1240
    assert(plugin_impl);
12✔
1241

1242
    plugin_impl->disable();
12✔
1243
    plugin_impl->deinit();
12✔
1244

1245
    // Remove first, so it won't get enabled/disabled anymore.
1246
    {
1247
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
24✔
1248
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
12✔
1249
        if (found != _plugin_impls.end()) {
12✔
1250
            _plugin_impls.erase(found);
12✔
1251
        }
1252
    }
1253
}
12✔
1254

1255
void SystemImpl::call_user_callback_located(
14✔
1256
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1257
{
1258
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
14✔
1259
}
14✔
1260

1261
void SystemImpl::param_changed(const std::string& name)
×
1262
{
1263
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1264

1265
    for (auto& callback : _param_changed_callbacks) {
×
1266
        callback.second(name);
×
1267
    }
1268
}
×
1269

1270
void SystemImpl::register_param_changed_handler(
1✔
1271
    const ParamChangedCallback& callback, const void* cookie)
1272
{
1273
    if (!callback) {
1✔
1274
        LogErr() << "No callback for param_changed_handler supplied.";
×
1275
        return;
×
1276
    }
1277

1278
    if (!cookie) {
1✔
1279
        LogErr() << "No callback for param_changed_handler supplied.";
×
1280
        return;
×
1281
    }
1282

1283
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
2✔
1284

1285
    _param_changed_callbacks[cookie] = callback;
1✔
1286
}
1287

1288
void SystemImpl::unregister_param_changed_handler(const void* cookie)
1✔
1289
{
1290
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
1✔
1291

1292
    auto it = _param_changed_callbacks.find(cookie);
1✔
1293
    if (it == _param_changed_callbacks.end()) {
1✔
1294
        LogWarn() << "param_changed_handler for cookie not found";
×
1295
        return;
×
1296
    }
1297
    _param_changed_callbacks.erase(it);
1✔
1298
}
1299

1300
Time& SystemImpl::get_time()
39✔
1301
{
1302
    return _mavsdk_impl.time;
39✔
1303
}
1304

1305
void SystemImpl::subscribe_param_float(
×
1306
    const std::string& name,
1307
    const MavlinkParameterSender::ParamFloatChangedCallback& callback,
1308
    const void* cookie)
1309
{
1310
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1311
}
×
1312

1313
void SystemImpl::subscribe_param_int(
×
1314
    const std::string& name,
1315
    const MavlinkParameterSender::ParamIntChangedCallback& callback,
1316
    const void* cookie)
1317
{
1318
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1319
}
×
1320
void SystemImpl::subscribe_param_custom(
×
1321
    const std::string& name,
1322
    const MavlinkParameterSender::ParamCustomChangedCallback& callback,
1323
    const void* cookie)
1324
{
1325
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1326
}
×
1327

1328
MavlinkParameterSender* SystemImpl::param_sender(uint8_t component_id, bool extended)
24✔
1329
{
1330
    std::lock_guard<std::mutex> lock(_mavlink_parameter_senders_mutex);
48✔
1331

1332
    for (auto& entry : _mavlink_parameter_senders) {
26✔
1333
        if (entry.component_id == component_id && entry.extended == extended) {
18✔
1334
            return entry.parameter_sender.get();
16✔
1335
        }
1336
    }
1337

1338
    _mavlink_parameter_senders.push_back(
16✔
1339
        {std::make_unique<MavlinkParameterSender>(
1340
             *this,
1341
             _mavsdk_impl.mavlink_message_handler,
8✔
1342
             _mavsdk_impl.timeout_handler,
8✔
1343
             [this]() { return timeout_s(); },
41✔
1344
             component_id,
1345
             extended),
1346
         component_id,
1347
         extended});
1348

1349
    return _mavlink_parameter_senders.back().parameter_sender.get();
8✔
1350
}
1351

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