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

mavlink / MAVSDK / 4769418837

pending completion
4769418837

push

github

GitHub
Merge pull request #2024 from mavlink/update-mavlink

7422 of 24274 relevant lines covered (30.58%)

21.52 hits per line

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

40.76
/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 <cstdlib>
11
#include <functional>
12
#include <future>
13
#include <utility>
14

15
namespace mavsdk {
16

17
template class CallbackList<bool>;
18
template class CallbackList<System::ComponentType>;
19
template class CallbackList<System::ComponentType, uint8_t>;
20

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

45
SystemImpl::~SystemImpl()
14✔
46
{
47
    _should_exit = true;
14✔
48
    _mavsdk_impl.mavlink_message_handler.unregister_all(this);
14✔
49

50
    if (!_always_connected) {
14✔
51
        unregister_timeout_handler(_heartbeat_timeout_cookie);
7✔
52
    }
53

54
    if (_system_thread != nullptr) {
14✔
55
        _system_thread->join();
14✔
56
        delete _system_thread;
14✔
57
        _system_thread = nullptr;
14✔
58
    }
59
}
14✔
60

61
void SystemImpl::init(uint8_t system_id, uint8_t comp_id, bool connected)
14✔
62
{
63
    _target_address.system_id = system_id;
14✔
64
    // FIXME: for now use this as a default.
65
    _target_address.component_id = MAV_COMP_ID_AUTOPILOT1;
14✔
66

67
    if (connected) {
14✔
68
        _always_connected = true;
7✔
69
        set_connected();
7✔
70
    }
71

72
    _mavsdk_impl.mavlink_message_handler.register_one(
14✔
73
        MAVLINK_MSG_ID_HEARTBEAT,
74
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
19✔
75
        this);
76

77
    _mavsdk_impl.mavlink_message_handler.register_one(
14✔
78
        MAVLINK_MSG_ID_STATUSTEXT,
79
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
80
        this);
81

82
    _mavsdk_impl.mavlink_message_handler.register_one(
14✔
83
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
84
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
7✔
85
        this);
86

87
    // register_mavlink_command_handler(
88
    //    MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
89
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
90
    //        return process_autopilot_version_request(command);
91
    //    },
92
    //    this);
93

94
    //// TO-DO!
95
    // register_mavlink_command_handler(
96
    //    MAV_CMD_REQUEST_MESSAGE,
97
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
98
    //        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
99
    //    },
100
    //    this);
101

102
    add_new_component(comp_id);
14✔
103
}
14✔
104

105
bool SystemImpl::is_connected() const
12✔
106
{
107
    return _connected;
12✔
108
}
109

110
void SystemImpl::register_mavlink_message_handler(
71✔
111
    uint16_t msg_id, const MavlinkMessageHandler& callback, const void* cookie)
112
{
113
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, callback, cookie);
71✔
114
}
71✔
115

116
void SystemImpl::register_mavlink_message_handler(
7✔
117
    uint16_t msg_id, uint8_t cmp_id, const MavlinkMessageHandler& callback, const void* cookie)
118
{
119
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, cmp_id, callback, cookie);
7✔
120
}
7✔
121

122
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
123
{
124
    _mavsdk_impl.mavlink_message_handler.unregister_one(msg_id, cookie);
×
125
}
×
126

127
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
46✔
128
{
129
    _mavsdk_impl.mavlink_message_handler.unregister_all(cookie);
46✔
130
}
46✔
131

132
void SystemImpl::update_componentid_messages_handler(
×
133
    uint16_t msg_id, uint8_t cmp_id, const void* cookie)
134
{
135
    _mavsdk_impl.mavlink_message_handler.update_component_id(msg_id, cmp_id, cookie);
×
136
}
×
137

138
void SystemImpl::register_timeout_handler(
24✔
139
    const std::function<void()>& callback, double duration_s, void** cookie)
140
{
141
    _mavsdk_impl.timeout_handler.add(callback, duration_s, cookie);
24✔
142
}
24✔
143

144
void SystemImpl::refresh_timeout_handler(const void* cookie)
3✔
145
{
146
    _mavsdk_impl.timeout_handler.refresh(cookie);
3✔
147
}
3✔
148

149
void SystemImpl::unregister_timeout_handler(const void* cookie)
22✔
150
{
151
    _mavsdk_impl.timeout_handler.remove(cookie);
22✔
152
}
22✔
153

154
double SystemImpl::timeout_s() const
225✔
155
{
156
    return _mavsdk_impl.timeout_s();
225✔
157
}
158

159
void SystemImpl::enable_timesync()
×
160
{
161
    _timesync.enable();
×
162
}
×
163

164
System::IsConnectedHandle
165
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
166
{
167
    std::lock_guard<std::mutex> lock(_connection_mutex);
×
168
    return _is_connected_callbacks.subscribe(callback);
×
169
}
170

171
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
172
{
173
    _is_connected_callbacks.unsubscribe(handle);
×
174
}
×
175

176
void SystemImpl::add_call_every(std::function<void()> callback, float interval_s, void** cookie)
5✔
177
{
178
    _mavsdk_impl.call_every_handler.add(
10✔
179
        std::move(callback), static_cast<double>(interval_s), cookie);
5✔
180
}
5✔
181

182
void SystemImpl::change_call_every(float interval_s, const void* cookie)
×
183
{
184
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
185
}
×
186

187
void SystemImpl::reset_call_every(const void* cookie)
×
188
{
189
    _mavsdk_impl.call_every_handler.reset(cookie);
×
190
}
×
191

192
void SystemImpl::remove_call_every(const void* cookie)
10✔
193
{
194
    _mavsdk_impl.call_every_handler.remove(cookie);
10✔
195
}
10✔
196

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

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

213
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
19✔
214
{
215
    mavlink_heartbeat_t heartbeat;
19✔
216
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
19✔
217

218
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
19✔
219
        _autopilot = Autopilot::Px4;
×
220
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
19✔
221
        _autopilot = Autopilot::ArduPilot;
×
222
    }
223

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

239
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
19✔
240
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
9✔
241
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
9✔
242
    }
243
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
19✔
244
        _flight_mode =
×
245
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
246
    }
247

248
    set_connected();
19✔
249
}
19✔
250

251
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
252
{
253
    mavlink_statustext_t statustext;
3✔
254
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
255

256
    const auto maybe_result = _statustext_handler.process(statustext);
6✔
257

258
    if (maybe_result.has_value()) {
3✔
259
        LogDebug() << "MAVLink: "
6✔
260
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
261
                   << maybe_result.value().text;
9✔
262

263
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
6✔
264
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
265
            entry.callback(maybe_result.value());
3✔
266
        }
267
    }
268
}
3✔
269

270
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
7✔
271
{
272
    mavlink_autopilot_version_t autopilot_version;
7✔
273
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
7✔
274

275
    _mission_transfer.set_int_messages_supported(
7✔
276
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
7✔
277
}
7✔
278

279
void SystemImpl::heartbeats_timed_out()
×
280
{
281
    LogInfo() << "heartbeats timed out";
×
282
    set_disconnected();
×
283
}
×
284

285
void SystemImpl::system_thread()
14✔
286
{
287
    SteadyTimePoint last_ping_time{};
14✔
288

289
    while (!_should_exit) {
758✔
290
        _params.do_work();
744✔
291
        _command_sender.do_work();
744✔
292
        _timesync.do_work();
743✔
293
        _mission_transfer.do_work();
744✔
294

295
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
744✔
296
            if (_connected) {
14✔
297
                _ping.run_once();
7✔
298
            }
299
            last_ping_time = _mavsdk_impl.time.steady_time();
14✔
300
        }
301

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

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

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

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

370
void SystemImpl::add_new_component(uint8_t component_id)
315✔
371
{
372
    if (component_id == 0) {
315✔
373
        return;
7✔
374
    }
375

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

516
    send_command_async(command, callback);
6✔
517
}
6✔
518

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

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

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

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

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

552
        if (!_connected) {
26✔
553
            if (!_components.empty()) {
14✔
554
                LogDebug() << "Discovered " << _components.size() << " component(s)";
7✔
555
            }
556

557
            _connected = true;
14✔
558

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

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

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

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

582
        } else if (_connected && !_always_connected) {
12✔
583
            refresh_timeout_handler(_heartbeat_timeout_cookie);
3✔
584
        }
585
        // If not yet connected there is nothing to do/
586
    }
587
    if (enable_needed) {
26✔
588
        if (has_autopilot()) {
14✔
589
            send_autopilot_version_request_async(nullptr);
6✔
590
        }
591

592
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
28✔
593
        for (auto plugin_impl : _plugin_impls) {
14✔
594
            plugin_impl->enable();
×
595
        }
596
    }
597
}
26✔
598

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

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

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

615
    _mavsdk_impl.stop_sending_heartbeats();
×
616

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

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

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

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

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

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

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

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

660
MAVLinkParameters::Result SystemImpl::set_param(
×
661
    const std::string& name,
662
    MAVLinkParameters::ParamValue value,
663
    std::optional<uint8_t> maybe_component_id,
664
    bool extended)
665
{
666
    return _params.set_param(name, value, maybe_component_id, extended);
×
667
}
668

669
MAVLinkParameters::Result SystemImpl::set_param_float(
1✔
670
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
671
{
672
    return _params.set_param_float(name, value, maybe_component_id, extended);
1✔
673
}
674

675
MAVLinkParameters::Result SystemImpl::set_param_int(
1✔
676
    const std::string& name,
677
    int32_t value,
678
    std::optional<uint8_t> maybe_component_id,
679
    bool extended)
680
{
681
    return _params.set_param_int(name, value, maybe_component_id, extended);
1✔
682
}
683

684
MAVLinkParameters::Result
685
SystemImpl::set_param_custom(const std::string& name, const std::string& value)
1✔
686
{
687
    return _params.set_param_custom(name, value);
1✔
688
}
689

690
std::map<std::string, MAVLinkParameters::ParamValue> SystemImpl::get_all_params()
1✔
691
{
692
    return _params.get_all_params();
1✔
693
}
694

695
void SystemImpl::set_param_async(
×
696
    const std::string& name,
697
    MAVLinkParameters::ParamValue value,
698
    const SetParamCallback& callback,
699
    const void* cookie,
700
    std::optional<uint8_t> maybe_component_id,
701
    bool extended)
702
{
703
    _params.set_param_async(name, value, callback, cookie, maybe_component_id, extended);
×
704
}
×
705

706
void SystemImpl::set_param_float_async(
×
707
    const std::string& name,
708
    float value,
709
    const SetParamCallback& callback,
710
    const void* cookie,
711
    std::optional<uint8_t> maybe_component_id,
712
    bool extended)
713
{
714
    _params.set_param_float_async(name, value, callback, cookie, maybe_component_id, extended);
×
715
}
×
716

717
void SystemImpl::set_param_int_async(
×
718
    const std::string& name,
719
    int32_t value,
720
    const SetParamCallback& callback,
721
    const void* cookie,
722
    std::optional<uint8_t> maybe_component_id,
723
    bool extended)
724
{
725
    _params.set_param_int_async(name, value, callback, cookie, maybe_component_id, extended);
×
726
}
×
727

728
std::pair<MAVLinkParameters::Result, float> SystemImpl::get_param_float(
2✔
729
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
730
{
731
    return _params.get_param_float(name, maybe_component_id, extended);
2✔
732
}
733

734
std::pair<MAVLinkParameters::Result, int> SystemImpl::get_param_int(
2✔
735
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
736
{
737
    return _params.get_param_int(name, maybe_component_id, extended);
2✔
738
}
739

740
std::pair<MAVLinkParameters::Result, std::string>
741
SystemImpl::get_param_custom(const std::string& name)
2✔
742
{
743
    return _params.get_param_custom(name);
2✔
744
}
745

746
void SystemImpl::get_param_async(
×
747
    const std::string& name,
748
    MAVLinkParameters::ParamValue value,
749
    const GetParamAnyCallback& callback,
750
    const void* cookie,
751
    std::optional<uint8_t> maybe_component_id,
752
    bool extended)
753
{
754
    _params.get_param_async(name, value, callback, cookie, maybe_component_id, extended);
×
755
}
×
756

757
void SystemImpl::get_param_float_async(
×
758
    const std::string& name,
759
    const GetParamFloatCallback& callback,
760
    const void* cookie,
761
    std::optional<uint8_t> maybe_component_id,
762
    bool extended)
763
{
764
    _params.get_param_float_async(name, callback, cookie, maybe_component_id, extended);
×
765
}
×
766

767
void SystemImpl::get_param_int_async(
×
768
    const std::string& name,
769
    const GetParamIntCallback& callback,
770
    const void* cookie,
771
    std::optional<uint8_t> maybe_component_id,
772
    bool extended)
773
{
774
    _params.get_param_int_async(name, callback, cookie, maybe_component_id, extended);
×
775
}
×
776

777
void SystemImpl::get_param_custom_async(
×
778
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
779
{
780
    _params.get_param_custom_async(name, callback, cookie);
×
781
}
×
782

783
void SystemImpl::cancel_all_param(const void* cookie)
2✔
784
{
785
    _params.cancel_all_param(cookie);
2✔
786
}
2✔
787

788
MavlinkCommandSender::Result
789
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
790
{
791
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
792
        make_command_flight_mode(system_mode, component_id);
×
793

794
    if (result.first != MavlinkCommandSender::Result::Success) {
×
795
        return result.first;
×
796
    }
797

798
    return send_command(result.second);
×
799
}
800

801
void SystemImpl::set_flight_mode_async(
×
802
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
803
{
804
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
805
        make_command_flight_mode(system_mode, component_id);
×
806

807
    if (result.first != MavlinkCommandSender::Result::Success) {
×
808
        if (callback) {
×
809
            callback(result.first, NAN);
×
810
        }
811
        return;
×
812
    }
813

814
    send_command_async(result.second, callback);
×
815
}
816

817
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
818
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
819
{
820
    if (_autopilot == Autopilot::ArduPilot) {
×
821
        return make_command_ardupilot_mode(flight_mode, component_id);
×
822
    } else {
823
        return make_command_px4_mode(flight_mode, component_id);
×
824
    }
825
}
826

827
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
828
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
829
{
830
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
831
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
832
    const uint8_t mode_type =
×
833
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
834

835
    MavlinkCommandSender::CommandLong command{};
×
836

837
    command.command = MAV_CMD_DO_SET_MODE;
×
838
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
839

840
    switch (_vehicle_type) {
×
841
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
842
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER:
843
            if (flight_mode_to_ardupilot_rover_mode(flight_mode) == ardupilot::RoverMode::Unknown) {
×
844
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
845
                MavlinkCommandSender::CommandLong empty_command{};
×
846
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
847
            } else {
848
                command.params.maybe_param2 =
×
849
                    static_cast<float>(flight_mode_to_ardupilot_rover_mode(flight_mode));
×
850
            }
851
            break;
×
852
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
853
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
854
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
855
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
856
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
857
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
858
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
859
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
860
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
861
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
862
                MavlinkCommandSender::CommandLong empty_command{};
×
863
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
864
            } else {
865
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
866
            }
867
            break;
×
868
        }
869

870
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
871
        case MAV_TYPE::MAV_TYPE_COAXIAL:
872
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
873
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
874
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
875
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
876
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
877
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
878
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
879
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
880
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
881
                MavlinkCommandSender::CommandLong empty_command{};
×
882
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
883
            } else {
884
                command.params.maybe_param2 =
×
885
                    static_cast<float>(flight_mode_to_ardupilot_copter_mode(flight_mode));
×
886
            }
887
            break;
×
888
        }
889

890
        default:
×
891
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
892
                     << _vehicle_type;
×
893
            MavlinkCommandSender::CommandLong empty_command{};
×
894
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
895
    }
896
    command.target_component_id = component_id;
×
897

898
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
899
}
900
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
901
{
902
    switch (flight_mode) {
×
903
        case FlightMode::Mission:
×
904
            return ardupilot::RoverMode::Auto;
×
905
        case FlightMode::Acro:
×
906
            return ardupilot::RoverMode::Acro;
×
907
        case FlightMode::Hold:
×
908
            return ardupilot::RoverMode::Hold;
×
909
        case FlightMode::ReturnToLaunch:
×
910
            return ardupilot::RoverMode::RTL;
×
911
        case FlightMode::Manual:
×
912
            return ardupilot::RoverMode::Manual;
×
913
        case FlightMode::FollowMe:
×
914
            return ardupilot::RoverMode::Follow;
×
915
        case FlightMode::Offboard:
×
916
            return ardupilot::RoverMode::Guided;
×
917
        case FlightMode::Unknown:
×
918
        case FlightMode::Ready:
919
        case FlightMode::Takeoff:
920
        case FlightMode::Land:
921
        case FlightMode::Altctl:
922
        case FlightMode::Posctl:
923
        case FlightMode::Rattitude:
924
        case FlightMode::Stabilized:
925
        default:
926
            return ardupilot::RoverMode::Unknown;
×
927
    }
928
}
929
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
930
{
931
    switch (flight_mode) {
×
932
        case FlightMode::Mission:
×
933
            return ardupilot::CopterMode::Auto;
×
934
        case FlightMode::Acro:
×
935
            return ardupilot::CopterMode::Acro;
×
936
        case FlightMode::Hold:
×
937
            return ardupilot::CopterMode::Loiter;
×
938
        case FlightMode::ReturnToLaunch:
×
939
            return ardupilot::CopterMode::Rtl;
×
940
        case FlightMode::Land:
×
941
            return ardupilot::CopterMode::Land;
×
942
        case FlightMode::Manual:
×
943
            return ardupilot::CopterMode::Stabilize;
×
944
        case FlightMode::FollowMe:
×
945
            return ardupilot::CopterMode::Follow;
×
946
        case FlightMode::Offboard:
×
947
            return ardupilot::CopterMode::Guided;
×
948
        case FlightMode::Altctl:
×
949
            return ardupilot::CopterMode::AltHold;
×
950
        case FlightMode::Posctl:
×
951
            return ardupilot::CopterMode::PosHold;
×
952
        case FlightMode::Stabilized:
×
953
            return ardupilot::CopterMode::Stabilize;
×
954
        case FlightMode::Unknown:
×
955
        case FlightMode::Ready:
956
        case FlightMode::Takeoff:
957
        case FlightMode::Rattitude:
958
        default:
959
            return ardupilot::CopterMode::Unknown;
×
960
    }
961
}
962
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
963
{
964
    switch (flight_mode) {
×
965
        case FlightMode::Mission:
×
966
            return ardupilot::PlaneMode::Auto;
×
967
        case FlightMode::Acro:
×
968
            return ardupilot::PlaneMode::Acro;
×
969
        case FlightMode::Hold:
×
970
            return ardupilot::PlaneMode::Loiter;
×
971
        case FlightMode::ReturnToLaunch:
×
972
            return ardupilot::PlaneMode::Rtl;
×
973
        case FlightMode::Manual:
×
974
            return ardupilot::PlaneMode::Manual;
×
975
        case FlightMode::FBWA:
×
976
            return ardupilot::PlaneMode::Fbwa;
×
977
        case FlightMode::Stabilized:
×
978
            return ardupilot::PlaneMode::Stabilize;
×
979
        case FlightMode::Unknown:
×
980
            return ardupilot::PlaneMode::Unknown;
×
981
        default:
×
982
            return ardupilot::PlaneMode::Unknown;
×
983
    }
984
}
985

986
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
987
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
988
{
989
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
990
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
991

992
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
993

994
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
995
    //       but want to be rather safe than sorry.
996
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
997
    uint8_t custom_sub_mode = 0;
×
998

999
    switch (flight_mode) {
×
1000
        case FlightMode::Hold:
×
1001
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1002
            break;
×
1003
        case FlightMode::ReturnToLaunch:
×
1004
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1005
            break;
×
1006
        case FlightMode::Takeoff:
×
1007
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1008
            break;
×
1009
        case FlightMode::Land:
×
1010
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1011
            break;
×
1012
        case FlightMode::Mission:
×
1013
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1014
            break;
×
1015
        case FlightMode::FollowMe:
×
1016
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1017
            break;
×
1018
        case FlightMode::Offboard:
×
1019
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1020
            break;
×
1021
        case FlightMode::Manual:
×
1022
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1023
            break;
×
1024
        case FlightMode::Posctl:
×
1025
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1026
            break;
×
1027
        case FlightMode::Altctl:
×
1028
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1029
            break;
×
1030
        case FlightMode::Rattitude:
×
1031
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1032
            break;
×
1033
        case FlightMode::Acro:
×
1034
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1035
            break;
×
1036
        case FlightMode::Stabilized:
×
1037
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1038
            break;
×
1039
        default:
×
1040
            LogErr() << "Unknown Flight mode.";
×
1041
            MavlinkCommandSender::CommandLong empty_command{};
×
1042
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1043
    }
1044

1045
    MavlinkCommandSender::CommandLong command{};
×
1046

1047
    command.command = MAV_CMD_DO_SET_MODE;
×
1048
    command.params.maybe_param1 = static_cast<float>(mode);
×
1049
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1050
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1051
    command.target_component_id = component_id;
×
1052

1053
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1054
}
1055

1056
FlightMode SystemImpl::get_flight_mode() const
6✔
1057
{
1058
    return _flight_mode;
6✔
1059
}
1060

1061
void SystemImpl::receive_float_param(
×
1062
    MAVLinkParameters::Result result,
1063
    MAVLinkParameters::ParamValue value,
1064
    const GetParamFloatCallback& callback)
1065
{
1066
    if (callback) {
×
1067
        if (result == MAVLinkParameters::Result::Success) {
×
1068
            callback(result, value.get<float>());
×
1069
        } else {
1070
            callback(result, NAN);
×
1071
        }
1072
    }
1073
}
×
1074

1075
void SystemImpl::receive_int_param(
×
1076
    MAVLinkParameters::Result result,
1077
    MAVLinkParameters::ParamValue value,
1078
    const GetParamIntCallback& callback)
1079
{
1080
    if (callback) {
×
1081
        if (result == MAVLinkParameters::Result::Success) {
×
1082
            callback(result, value.get<int32_t>());
×
1083
        } else {
1084
            callback(result, 0);
×
1085
        }
1086
    }
1087
}
×
1088

1089
uint8_t SystemImpl::get_autopilot_id() const
32✔
1090
{
1091
    for (auto compid : _components)
35✔
1092
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
25✔
1093
            return compid;
22✔
1094
        }
1095
    // FIXME: Not sure what should be returned if autopilot is not found
1096
    return uint8_t(0);
10✔
1097
}
1098

1099
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1100
{
1101
    std::vector<uint8_t> camera_ids{};
×
1102

1103
    for (auto compid : _components)
×
1104
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1105
            camera_ids.push_back(compid);
×
1106
        }
1107
    return camera_ids;
×
1108
}
1109

1110
uint8_t SystemImpl::get_gimbal_id() const
×
1111
{
1112
    for (auto compid : _components)
×
1113
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1114
            return compid;
×
1115
        }
1116
    return uint8_t(0);
×
1117
}
1118

1119
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
1✔
1120
{
1121
    if (_target_address.system_id == 0 && _components.empty()) {
1✔
1122
        return MavlinkCommandSender::Result::NoSystem;
×
1123
    }
1124
    command.target_system_id = get_system_id();
1✔
1125
    return _command_sender.send_command(command);
1✔
1126
}
1127

1128
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1129
{
1130
    if (_target_address.system_id == 0 && _components.empty()) {
×
1131
        return MavlinkCommandSender::Result::NoSystem;
×
1132
    }
1133
    command.target_system_id = get_system_id();
×
1134
    return _command_sender.send_command(command);
×
1135
}
1136

1137
void SystemImpl::send_command_async(
15✔
1138
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1139
{
1140
    if (_target_address.system_id == 0 && _components.empty()) {
15✔
1141
        if (callback) {
×
1142
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1143
        }
1144
        return;
×
1145
    }
1146
    command.target_system_id = get_system_id();
15✔
1147

1148
    _command_sender.queue_command_async(command, callback);
15✔
1149
}
1150

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

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

1165
MavlinkCommandSender::Result
1166
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1167
{
1168
    MavlinkCommandSender::CommandLong command =
×
1169
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1170
    return send_command(command);
×
1171
}
1172

1173
void SystemImpl::set_msg_rate_async(
1✔
1174
    uint16_t message_id,
1175
    double rate_hz,
1176
    const CommandResultCallback& callback,
1177
    uint8_t component_id)
1178
{
1179
    MavlinkCommandSender::CommandLong command =
1✔
1180
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1181
    send_command_async(command, callback);
1✔
1182
}
1✔
1183

1184
MavlinkCommandSender::CommandLong
1185
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1186
{
1187
    MavlinkCommandSender::CommandLong command{};
1✔
1188

1189
    // 0 to request default rate, -1 to stop stream
1190

1191
    float interval_us = 0.0f;
1✔
1192

1193
    if (rate_hz > 0) {
1✔
1194
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1195
    } else if (rate_hz < 0) {
×
1196
        interval_us = -1.0f;
×
1197
    }
1198

1199
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1200
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1201
    command.params.maybe_param2 = interval_us;
1✔
1202
    command.target_component_id = component_id;
1✔
1203

1204
    return command;
1✔
1205
}
1206

1207
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
7✔
1208
{
1209
    assert(plugin_impl);
7✔
1210

1211
    plugin_impl->init();
7✔
1212

1213
    {
1214
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
14✔
1215
        _plugin_impls.push_back(plugin_impl);
7✔
1216
    }
1217

1218
    // If we're connected already, let's enable it straightaway.
1219
    if (_connected) {
7✔
1220
        plugin_impl->enable();
7✔
1221
    }
1222
}
7✔
1223

1224
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
7✔
1225
{
1226
    assert(plugin_impl);
7✔
1227

1228
    plugin_impl->disable();
7✔
1229
    plugin_impl->deinit();
7✔
1230

1231
    // Remove first, so it won't get enabled/disabled anymore.
1232
    {
1233
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
14✔
1234
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
7✔
1235
        if (found != _plugin_impls.end()) {
7✔
1236
            _plugin_impls.erase(found);
7✔
1237
        }
1238
    }
1239
}
7✔
1240

1241
void SystemImpl::call_user_callback_located(
17✔
1242
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1243
{
1244
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
17✔
1245
}
17✔
1246

1247
void SystemImpl::param_changed(const std::string& name)
×
1248
{
1249
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1250

1251
    for (auto& callback : _param_changed_callbacks) {
×
1252
        callback.second(name);
×
1253
    }
1254
}
×
1255

1256
void SystemImpl::register_param_changed_handler(
1✔
1257
    const ParamChangedCallback& callback, const void* cookie)
1258
{
1259
    if (!callback) {
1✔
1260
        LogErr() << "No callback for param_changed_handler supplied.";
×
1261
        return;
×
1262
    }
1263

1264
    if (!cookie) {
1✔
1265
        LogErr() << "No callback for param_changed_handler supplied.";
×
1266
        return;
×
1267
    }
1268

1269
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
2✔
1270

1271
    _param_changed_callbacks[cookie] = callback;
1✔
1272
}
1273

1274
void SystemImpl::unregister_param_changed_handler(const void* cookie)
1✔
1275
{
1276
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
1✔
1277

1278
    auto it = _param_changed_callbacks.find(cookie);
1✔
1279
    if (it == _param_changed_callbacks.end()) {
1✔
1280
        LogWarn() << "param_changed_handler for cookie not found";
×
1281
        return;
×
1282
    }
1283
    _param_changed_callbacks.erase(it);
1✔
1284
}
1285

1286
Time& SystemImpl::get_time()
36✔
1287
{
1288
    return _mavsdk_impl.time;
36✔
1289
}
1290

1291
void SystemImpl::subscribe_param_float(
×
1292
    const std::string& name,
1293
    const MAVLinkParameters::ParamFloatChangedCallback& callback,
1294
    const void* cookie)
1295
{
1296
    _params.subscribe_param_float_changed(name, callback, cookie);
×
1297
}
×
1298

1299
void SystemImpl::subscribe_param_int(
×
1300
    const std::string& name,
1301
    const MAVLinkParameters::ParamIntChangedCallback& callback,
1302
    const void* cookie)
1303
{
1304
    _params.subscribe_param_int_changed(name, callback, cookie);
×
1305
}
×
1306
void SystemImpl::subscribe_param_custom(
×
1307
    const std::string& name,
1308
    const MAVLinkParameters::ParamCustomChangedCallback& callback,
1309
    const void* cookie)
1310
{
1311
    _params.subscribe_param_custom_changed(name, callback, cookie);
×
1312
}
×
1313

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