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

mavlink / MAVSDK / 8102998379

29 Feb 2024 09:43PM UTC coverage: 36.315% (-0.009%) from 36.324%
8102998379

push

github

web-flow
Merge pull request #2233 from jjisolo/patch-1

Add missing switch-case parameter

0 of 2 new or added lines in 1 file covered. (0.0%)

3 existing lines in 2 files now uncovered.

10081 of 27760 relevant lines covered (36.31%)

129.44 hits per line

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

41.15
/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 "server_component_impl.h"
6
#include "plugin_impl_base.h"
7
#include "px4_custom_mode.h"
8
#include "ardupilot_custom_mode.h"
9
#include "request_message.h"
10
#include "callback_list.tpp"
11
#include "unused.h"
12
#include <cassert>
13
#include <cstdlib>
14
#include <functional>
15
#include <future>
16
#include <utility>
17

18
namespace mavsdk {
19

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

24
SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) :
68✔
25
    _mavsdk_impl(mavsdk_impl),
26
    _command_sender(*this),
27
    _timesync(*this),
28
    _ping(*this),
29
    _mission_transfer_client(
30
        _mavsdk_impl.default_server_component_impl().sender(),
68✔
31
        _mavlink_message_handler,
68✔
32
        _mavsdk_impl.timeout_handler,
68✔
33
        [this]() { return timeout_s(); },
1✔
34
        [this]() { return autopilot(); }),
1✔
35
    _request_message(
36
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
68✔
37
    _mavlink_ftp_client(*this)
136✔
38
{
39
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
68✔
40
}
68✔
41

42
SystemImpl::~SystemImpl()
68✔
43
{
44
    _should_exit = true;
68✔
45
    _mavlink_message_handler.unregister_all(this);
68✔
46

47
    unregister_timeout_handler(_heartbeat_timeout_cookie);
68✔
48

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

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

62
    _mavlink_message_handler.register_one(
68✔
63
        MAVLINK_MSG_ID_HEARTBEAT,
64
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
83✔
65
        this);
66

67
    _mavlink_message_handler.register_one(
68✔
68
        MAVLINK_MSG_ID_STATUSTEXT,
69
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
70
        this);
71

72
    _mavlink_message_handler.register_one(
68✔
73
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
74
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
39✔
75
        this);
76

77
    // register_mavlink_command_handler(
78
    //    MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
79
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
80
    //        return process_autopilot_version_request(command);
81
    //    },
82
    //    this);
83

84
    //// TO-DO!
85
    // register_mavlink_command_handler(
86
    //    MAV_CMD_REQUEST_MESSAGE,
87
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
88
    //        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
89
    //    },
90
    //    this);
91

92
    add_new_component(comp_id);
68✔
93
}
68✔
94

95
bool SystemImpl::is_connected() const
34✔
96
{
97
    return _connected;
34✔
98
}
99

100
void SystemImpl::register_mavlink_message_handler(
233✔
101
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
102
{
103
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
233✔
104
}
233✔
105

106
void SystemImpl::register_mavlink_message_handler_with_compid(
7✔
107
    uint16_t msg_id,
108
    uint8_t component_id,
109
    const MavlinkMessageHandler::Callback& callback,
110
    const void* cookie)
111
{
112
    _mavlink_message_handler.register_one_with_component_id(msg_id, component_id, callback, cookie);
7✔
113
}
7✔
114

115
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
116
{
117
    _mavlink_message_handler.unregister_one(msg_id, cookie);
×
118
}
×
119

120
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
276✔
121
{
122
    _mavlink_message_handler.unregister_all(cookie);
276✔
123
}
276✔
124

125
void SystemImpl::update_component_id_messages_handler(
×
126
    uint16_t msg_id, uint8_t component_id, const void* cookie)
127
{
128
    _mavlink_message_handler.update_component_id(msg_id, component_id, cookie);
×
129
}
×
130

131
void SystemImpl::register_timeout_handler(
865✔
132
    const std::function<void()>& callback, double duration_s, void** cookie)
133
{
134
    _mavsdk_impl.timeout_handler.add(callback, duration_s, cookie);
865✔
135
}
865✔
136

137
void SystemImpl::refresh_timeout_handler(const void* cookie)
16✔
138
{
139
    _mavsdk_impl.timeout_handler.refresh(cookie);
16✔
140
}
16✔
141

142
void SystemImpl::unregister_timeout_handler(const void* cookie)
893✔
143
{
144
    _mavsdk_impl.timeout_handler.remove(cookie);
893✔
145
}
893✔
146

147
double SystemImpl::timeout_s() const
838✔
148
{
149
    return _mavsdk_impl.timeout_s();
838✔
150
}
151

152
void SystemImpl::enable_timesync()
×
153
{
154
    _timesync.enable();
×
155
}
×
156

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

164
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
165
{
166
    _is_connected_callbacks.unsubscribe(handle);
×
167
}
×
168

169
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
1,418✔
170
{
171
    _mavlink_message_handler.process_message(message);
1,418✔
172
}
1,418✔
173

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

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

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

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

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

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

211
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
83✔
212
{
213
    mavlink_heartbeat_t heartbeat;
83✔
214
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
83✔
215

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

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

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

246
    set_connected();
83✔
247
}
83✔
248

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

254
    const auto maybe_result = _statustext_handler.process(statustext);
6✔
255

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

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

268
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
39✔
269
{
270
    mavlink_autopilot_version_t autopilot_version;
39✔
271
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
39✔
272

273
    _mission_transfer_client.set_int_messages_supported(
39✔
274
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
39✔
275
}
39✔
276

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

283
void SystemImpl::system_thread()
68✔
284
{
285
    SteadyTimePoint last_ping_time{};
68✔
286

287
    while (!_should_exit) {
3,941✔
288
        {
289
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
7,746✔
290
            for (auto& entry : _mavlink_parameter_clients) {
4,260✔
291
                entry.parameter_client->do_work();
387✔
292
            }
293
        }
294
        _command_sender.do_work();
3,873✔
295
        _timesync.do_work();
3,873✔
296
        _mission_transfer_client.do_work();
3,873✔
297
        _mavlink_ftp_client.do_work();
3,873✔
298

299
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
3,873✔
300
            if (_connected && _autopilot != Autopilot::ArduPilot) {
68✔
301
                _ping.run_once();
×
302
            }
303
            last_ping_time = _mavsdk_impl.time.steady_time();
68✔
304
        }
305

306
        if (_connected) {
3,873✔
307
            // Work fairly fast if we're connected.
308
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
3,386✔
309
        } else {
310
            // Be less aggressive when unconnected.
311
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
487✔
312
        }
313
    }
314
}
68✔
315

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

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

355
System::ComponentType SystemImpl::component_type(uint8_t component_id)
136✔
356
{
357
    switch (component_id) {
136✔
358
        case MAV_COMP_ID_AUTOPILOT1:
66✔
359
            return System::ComponentType::AUTOPILOT;
66✔
360
        case MAV_COMP_ID_CAMERA:
2✔
361
        case MAV_COMP_ID_CAMERA2:
362
        case MAV_COMP_ID_CAMERA3:
363
        case MAV_COMP_ID_CAMERA4:
364
        case MAV_COMP_ID_CAMERA5:
365
        case MAV_COMP_ID_CAMERA6:
366
            return System::ComponentType::CAMERA;
2✔
367
        case MAV_COMP_ID_GIMBAL:
×
368
            return System::ComponentType::GIMBAL;
×
369
        default:
68✔
370
            return System::ComponentType::UNKNOWN;
68✔
371
    }
372
}
373

374
void SystemImpl::add_new_component(uint8_t component_id)
1,453✔
375
{
376
    if (component_id == 0) {
1,453✔
377
        return;
34✔
378
    }
379

380
    auto res_pair = _components.insert(component_id);
1,419✔
381
    if (res_pair.second) {
1,419✔
382
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
136✔
383
        _component_discovered_callbacks.queue(
68✔
384
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
385
        _component_discovered_id_callbacks.queue(
68✔
386
            component_type(component_id), component_id, [this](const auto& func) {
×
387
                call_user_callback(func);
×
388
            });
×
389
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
272✔
390
                   << ") added.";
272✔
391
    }
392
}
393

394
size_t SystemImpl::total_components() const
×
395
{
396
    return _components.size();
×
397
}
398

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

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

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

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

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

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

441
bool SystemImpl::is_standalone() const
×
442
{
443
    return !has_autopilot();
×
444
}
445

446
bool SystemImpl::has_autopilot() const
135✔
447
{
448
    return get_autopilot_id() != uint8_t(0);
135✔
449
}
450

451
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
452
{
453
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
454
}
455

456
bool SystemImpl::is_camera(uint8_t comp_id)
1✔
457
{
458
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
1✔
459
}
460

461
bool SystemImpl::has_camera(int camera_id) const
1✔
462
{
463
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
1✔
464

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

479
bool SystemImpl::has_gimbal() const
×
480
{
481
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
482
}
483

484
bool SystemImpl::send_message(mavlink_message_t& message)
×
485
{
486
    return _mavsdk_impl.send_message(message);
×
487
}
488

489
bool SystemImpl::queue_message(
548✔
490
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
491
{
492
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
548✔
493
}
494

495
void SystemImpl::send_autopilot_version_request()
×
496
{
497
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
498
    auto fut = prom.get_future();
×
499

500
    send_autopilot_version_request_async(
×
501
        [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
502

503
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
504
        _old_message_520_supported = false;
×
505
        LogWarn() << "Trying alternative command (512).";
×
506
        send_autopilot_version_request();
×
507
    }
508
}
×
509

510
void SystemImpl::send_autopilot_version_request_async(
33✔
511
    const MavlinkCommandSender::CommandResultCallback& callback)
512
{
513
    MavlinkCommandSender::CommandLong command{};
33✔
514
    command.target_component_id = get_autopilot_id();
33✔
515

516
    if (_old_message_520_supported) {
33✔
517
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
518
        // release.
519
        command.command = MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES;
33✔
520
        command.params.maybe_param1 = 1.0f;
33✔
521
    } else {
522
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
523
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_AUTOPILOT_VERSION)};
×
524
    }
525

526
    send_command_async(command, callback);
33✔
527
}
33✔
528

529
void SystemImpl::send_flight_information_request()
×
530
{
531
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
532
    auto fut = prom.get_future();
×
533

534
    MavlinkCommandSender::CommandLong command{};
×
535
    command.target_component_id = get_autopilot_id();
×
536

537
    if (_old_message_528_supported) {
×
538
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
539
        // release.
540
        command.command = MAV_CMD_REQUEST_FLIGHT_INFORMATION;
×
541
        command.params.maybe_param1 = 1.0f;
×
542
    } else {
543
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
544
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_FLIGHT_INFORMATION)};
×
545
    }
546

547
    send_command_async(
×
548
        command, [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
549
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
550
        _old_message_528_supported = false;
×
551
        LogWarn() << "Trying alternative command (512)..";
×
552
        send_flight_information_request();
×
553
    }
554
}
×
555

556
void SystemImpl::set_connected()
83✔
557
{
558
    bool enable_needed = false;
83✔
559
    {
560
        std::lock_guard<std::mutex> lock(_connection_mutex);
166✔
561

562
        if (!_connected) {
83✔
563
            if (!_components.empty()) {
67✔
564
                LogDebug() << "Discovered " << _components.size() << " component(s)";
67✔
565
            }
566

567
            _connected = true;
67✔
568

569
            // System with sysid 0 is a bit special: it is a placeholder for a connection initiated
570
            // by MAVSDK. As such, it should not be advertised as a newly discovered system.
571
            if (static_cast<int>(get_system_id()) != 0) {
67✔
572
                _mavsdk_impl.notify_on_discover();
67✔
573
            }
574

575
            // We call this later to avoid deadlocks on creating the server components.
576
            _mavsdk_impl.call_user_callback([this]() {
134✔
577
                // Send a heartbeat back immediately.
578
                _mavsdk_impl.start_sending_heartbeats();
579
            });
580

581
            register_timeout_handler(
67✔
582
                [this] { heartbeats_timed_out(); },
×
583
                HEARTBEAT_TIMEOUT_S,
584
                &_heartbeat_timeout_cookie);
585

586
            enable_needed = true;
67✔
587

588
            _is_connected_callbacks.queue(
67✔
589
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
590

591
        } else if (_connected) {
16✔
592
            refresh_timeout_handler(_heartbeat_timeout_cookie);
16✔
593
        }
594
        // If not yet connected there is nothing to do/
595
    }
596
    if (enable_needed) {
83✔
597
        if (has_autopilot()) {
67✔
598
            send_autopilot_version_request_async(nullptr);
33✔
599
        }
600

601
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
134✔
602
        for (auto plugin_impl : _plugin_impls) {
67✔
603
            plugin_impl->enable();
×
604
        }
605
    }
606
}
83✔
607

608
void SystemImpl::set_disconnected()
×
609
{
610
    {
611
        std::lock_guard<std::mutex> lock(_connection_mutex);
×
612

613
        // This might not be needed because this is probably called from the triggered
614
        // timeout anyway, but it should also do no harm.
615
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
616
        //_heartbeat_timeout_cookie = nullptr;
617

618
        _connected = false;
×
619
        _mavsdk_impl.notify_on_timeout();
×
620
        _is_connected_callbacks.queue(
×
621
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
622
    }
623

624
    _mavsdk_impl.stop_sending_heartbeats();
×
625

626
    {
627
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
628
        for (auto plugin_impl : _plugin_impls) {
×
629
            plugin_impl->disable();
×
630
        }
631
    }
632
}
×
633

634
uint8_t SystemImpl::get_system_id() const
619✔
635
{
636
    return _target_address.system_id;
619✔
637
}
638

639
std::vector<uint8_t> SystemImpl::component_ids() const
×
640
{
641
    return std::vector<uint8_t>{_components.begin(), _components.end()};
×
642
}
643

644
void SystemImpl::set_system_id(uint8_t system_id)
34✔
645
{
646
    _target_address.system_id = system_id;
34✔
647
}
34✔
648

649
uint8_t SystemImpl::get_own_system_id() const
1,137✔
650
{
651
    return _mavsdk_impl.get_own_system_id();
1,137✔
652
}
653

654
uint8_t SystemImpl::get_own_component_id() const
1,137✔
655
{
656
    return _mavsdk_impl.get_own_component_id();
1,137✔
657
}
658

659
MAV_TYPE SystemImpl::get_vehicle_type() const
×
660
{
661
    return _vehicle_type;
×
662
}
663

664
uint8_t SystemImpl::get_own_mav_type() const
×
665
{
666
    return _mavsdk_impl.get_mav_type();
×
667
}
668

669
MavlinkParameterClient::Result SystemImpl::set_param(
×
670
    const std::string& name,
671
    ParamValue value,
672
    std::optional<uint8_t> maybe_component_id,
673
    bool extended)
674
{
675
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
676
        ->set_param(name, value);
×
677
}
678

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

686
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
687
    const std::string& name,
688
    int32_t value,
689
    std::optional<uint8_t> maybe_component_id,
690
    bool extended)
691
{
692
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
693
        ->set_param_int(name, value);
4✔
694
}
695

696
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
697
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
698
{
699
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
700
        ->set_param_custom(name, value);
4✔
701
}
702

703
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
704
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
705
{
706
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
707
        ->get_all_params();
8✔
708
}
709

710
void SystemImpl::set_param_async(
×
711
    const std::string& name,
712
    ParamValue value,
713
    const SetParamCallback& callback,
714
    const void* cookie,
715
    std::optional<uint8_t> maybe_component_id,
716
    bool extended)
717
{
718
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
719
        ->set_param_async(name, value, callback, cookie);
×
720
}
×
721

722
void SystemImpl::set_param_float_async(
×
723
    const std::string& name,
724
    float value,
725
    const SetParamCallback& callback,
726
    const void* cookie,
727
    std::optional<uint8_t> maybe_component_id,
728
    bool extended)
729
{
730
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
731
        ->set_param_float_async(name, value, callback, cookie);
×
732
}
×
733

734
void SystemImpl::set_param_int_async(
×
735
    const std::string& name,
736
    int32_t value,
737
    const SetParamCallback& callback,
738
    const void* cookie,
739
    std::optional<uint8_t> maybe_component_id,
740
    bool extended)
741
{
742
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
743
        ->set_param_int_async(name, value, callback, cookie);
×
744
}
×
745

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

753
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
754
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
755
{
756
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
757
        ->get_param_int(name);
10✔
758
}
759

760
std::pair<MavlinkParameterClient::Result, std::string>
761
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
762
{
763
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
764
        ->get_param_custom(name);
8✔
765
}
766

767
void SystemImpl::get_param_async(
×
768
    const std::string& name,
769
    ParamValue value,
770
    const GetParamAnyCallback& callback,
771
    const void* cookie,
772
    std::optional<uint8_t> maybe_component_id,
773
    bool extended)
774
{
775
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
776
        ->get_param_async(name, value, callback, cookie);
×
777
}
×
778

779
void SystemImpl::get_param_float_async(
×
780
    const std::string& name,
781
    const GetParamFloatCallback& callback,
782
    const void* cookie,
783
    std::optional<uint8_t> maybe_component_id,
784
    bool extended)
785
{
786
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
787
        ->get_param_float_async(name, callback, cookie);
×
788
}
×
789

790
void SystemImpl::get_param_int_async(
4✔
791
    const std::string& name,
792
    const GetParamIntCallback& callback,
793
    const void* cookie,
794
    std::optional<uint8_t> maybe_component_id,
795
    bool extended)
796
{
797
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
798
        ->get_param_int_async(name, callback, cookie);
4✔
799
}
4✔
800

801
void SystemImpl::get_param_custom_async(
×
802
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
803
{
804
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
805
}
×
806

807
void SystemImpl::cancel_all_param(const void* cookie)
2✔
808
{
809
    UNUSED(cookie);
2✔
810
    // FIXME: this currently crashes on destruction
811
    // param_sender(1, false)->cancel_all_param(cookie);
812
}
2✔
813

814
MavlinkCommandSender::Result
815
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
816
{
817
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
818
        make_command_flight_mode(system_mode, component_id);
×
819

820
    if (result.first != MavlinkCommandSender::Result::Success) {
×
821
        return result.first;
×
822
    }
823

824
    return send_command(result.second);
×
825
}
826

827
void SystemImpl::set_flight_mode_async(
×
828
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
829
{
830
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
831
        make_command_flight_mode(system_mode, component_id);
×
832

833
    if (result.first != MavlinkCommandSender::Result::Success) {
×
834
        if (callback) {
×
835
            callback(result.first, NAN);
×
836
        }
837
        return;
×
838
    }
839

840
    send_command_async(result.second, callback);
×
841
}
842

843
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
844
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
845
{
846
    if (_autopilot == Autopilot::ArduPilot) {
×
847
        return make_command_ardupilot_mode(flight_mode, component_id);
×
848
    } else {
849
        return make_command_px4_mode(flight_mode, component_id);
×
850
    }
851
}
852

853
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
854
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
855
{
856
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
857
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
858
    const uint8_t mode_type =
×
859
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
860

861
    MavlinkCommandSender::CommandLong command{};
×
862

863
    command.command = MAV_CMD_DO_SET_MODE;
×
864
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
865

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

897
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
898
        case MAV_TYPE::MAV_TYPE_COAXIAL:
899
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
900
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
901
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
902
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
903
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
904
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
905
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
906
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
907
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
908
                MavlinkCommandSender::CommandLong empty_command{};
×
909
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
910
            } else {
911
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
912
            }
913
            break;
×
914
        }
915

916
        default:
×
917
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
918
                     << _vehicle_type;
×
919
            MavlinkCommandSender::CommandLong empty_command{};
×
920
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
921
    }
922
    command.target_component_id = component_id;
×
923

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

1014
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1015
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1016
{
1017
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1018
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1019

1020
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1021

1022
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1023
    //       but want to be rather safe than sorry.
1024
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1025
    uint8_t custom_sub_mode = 0;
×
1026

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

1073
    MavlinkCommandSender::CommandLong command{};
×
1074

1075
    command.command = MAV_CMD_DO_SET_MODE;
×
1076
    command.params.maybe_param1 = static_cast<float>(mode);
×
1077
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1078
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1079
    command.target_component_id = component_id;
×
1080

1081
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1082
}
1083

1084
FlightMode SystemImpl::get_flight_mode() const
6✔
1085
{
1086
    return _flight_mode;
6✔
1087
}
1088

1089
void SystemImpl::receive_float_param(
×
1090
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1091
{
1092
    if (callback) {
×
1093
        if (result == MavlinkParameterClient::Result::Success) {
×
1094
            callback(result, value.get<float>());
×
1095
        } else {
1096
            callback(result, NAN);
×
1097
        }
1098
    }
1099
}
×
1100

1101
void SystemImpl::receive_int_param(
×
1102
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1103
{
1104
    if (callback) {
×
1105
        if (result == MavlinkParameterClient::Result::Success) {
×
1106
            callback(result, value.get<int32_t>());
×
1107
        } else {
1108
            callback(result, 0);
×
1109
        }
1110
    }
1111
}
×
1112

1113
uint8_t SystemImpl::get_autopilot_id() const
675✔
1114
{
1115
    for (auto compid : _components)
710✔
1116
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
675✔
1117
            return compid;
640✔
1118
        }
1119
    // FIXME: Not sure what should be returned if autopilot is not found
1120
    return uint8_t(0);
35✔
1121
}
1122

1123
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1124
{
1125
    std::vector<uint8_t> camera_ids{};
×
1126

1127
    for (auto compid : _components)
×
1128
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1129
            camera_ids.push_back(compid);
×
1130
        }
1131
    return camera_ids;
×
1132
}
1133

1134
uint8_t SystemImpl::get_gimbal_id() const
×
1135
{
1136
    for (auto compid : _components)
×
1137
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1138
            return compid;
×
1139
        }
1140
    return uint8_t(0);
×
1141
}
1142

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

1152
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1153
{
1154
    if (_target_address.system_id == 0 && _components.empty()) {
×
1155
        return MavlinkCommandSender::Result::NoSystem;
×
1156
    }
1157
    command.target_system_id = get_system_id();
×
1158
    return _command_sender.send_command(command);
×
1159
}
1160

1161
void SystemImpl::send_command_async(
39✔
1162
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1163
{
1164
    if (_target_address.system_id == 0 && _components.empty()) {
39✔
1165
        if (callback) {
×
1166
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1167
        }
1168
        return;
×
1169
    }
1170
    command.target_system_id = get_system_id();
39✔
1171

1172
    _command_sender.queue_command_async(command, callback);
39✔
1173
}
1174

1175
void SystemImpl::send_command_async(
×
1176
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1177
{
1178
    if (_target_address.system_id == 0 && _components.empty()) {
×
1179
        if (callback) {
×
1180
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1181
        }
1182
        return;
×
1183
    }
1184
    command.target_system_id = get_system_id();
×
1185

1186
    _command_sender.queue_command_async(command, callback);
×
1187
}
1188

1189
MavlinkCommandSender::Result
1190
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1191
{
1192
    MavlinkCommandSender::CommandLong command =
×
1193
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1194
    return send_command(command);
×
1195
}
1196

1197
void SystemImpl::set_msg_rate_async(
1✔
1198
    uint16_t message_id,
1199
    double rate_hz,
1200
    const CommandResultCallback& callback,
1201
    uint8_t component_id)
1202
{
1203
    MavlinkCommandSender::CommandLong command =
1✔
1204
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1205
    send_command_async(command, callback);
1✔
1206
}
1✔
1207

1208
MavlinkCommandSender::CommandLong
1209
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1210
{
1211
    MavlinkCommandSender::CommandLong command{};
1✔
1212

1213
    // 0 to request default rate, -1 to stop stream
1214

1215
    float interval_us = 0.0f;
1✔
1216

1217
    if (rate_hz > 0) {
1✔
1218
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1219
    } else if (rate_hz < 0) {
×
1220
        interval_us = -1.0f;
×
1221
    }
1222

1223
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1224
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1225
    command.params.maybe_param2 = interval_us;
1✔
1226
    command.target_component_id = component_id;
1✔
1227

1228
    return command;
1✔
1229
}
1230

1231
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
36✔
1232
{
1233
    assert(plugin_impl);
36✔
1234

1235
    plugin_impl->init();
36✔
1236

1237
    {
1238
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
72✔
1239
        _plugin_impls.push_back(plugin_impl);
36✔
1240
    }
1241

1242
    // If we're connected already, let's enable it straightaway.
1243
    if (_connected) {
36✔
1244
        plugin_impl->enable();
36✔
1245
    }
1246
}
36✔
1247

1248
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
36✔
1249
{
1250
    assert(plugin_impl);
36✔
1251

1252
    plugin_impl->disable();
36✔
1253
    plugin_impl->deinit();
36✔
1254

1255
    // Remove first, so it won't get enabled/disabled anymore.
1256
    {
1257
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
72✔
1258
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
36✔
1259
        if (found != _plugin_impls.end()) {
36✔
1260
            _plugin_impls.erase(found);
36✔
1261
        }
1262
    }
1263
}
36✔
1264

1265
void SystemImpl::call_user_callback_located(
666✔
1266
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1267
{
1268
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
666✔
1269
}
666✔
1270

1271
void SystemImpl::param_changed(const std::string& name)
×
1272
{
1273
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1274

1275
    for (auto& callback : _param_changed_callbacks) {
×
1276
        callback.second(name);
×
1277
    }
1278
}
×
1279

1280
void SystemImpl::register_param_changed_handler(
1✔
1281
    const ParamChangedCallback& callback, const void* cookie)
1282
{
1283
    if (!callback) {
1✔
1284
        LogErr() << "No callback for param_changed_handler supplied.";
×
1285
        return;
×
1286
    }
1287

1288
    if (!cookie) {
1✔
1289
        LogErr() << "No callback for param_changed_handler supplied.";
×
1290
        return;
×
1291
    }
1292

1293
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
2✔
1294

1295
    _param_changed_callbacks[cookie] = callback;
1✔
1296
}
1297

1298
void SystemImpl::unregister_param_changed_handler(const void* cookie)
1✔
1299
{
1300
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
1✔
1301

1302
    auto it = _param_changed_callbacks.find(cookie);
1✔
1303
    if (it == _param_changed_callbacks.end()) {
1✔
1304
        LogWarn() << "param_changed_handler for cookie not found";
×
1305
        return;
×
1306
    }
1307
    _param_changed_callbacks.erase(it);
1✔
1308
}
1309

1310
Time& SystemImpl::get_time()
84✔
1311
{
1312
    return _mavsdk_impl.time;
84✔
1313
}
1314

1315
void SystemImpl::subscribe_param_float(
×
1316
    const std::string& name,
1317
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1318
    const void* cookie)
1319
{
1320
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1321
}
×
1322

1323
void SystemImpl::subscribe_param_int(
×
1324
    const std::string& name,
1325
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1326
    const void* cookie)
1327
{
1328
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1329
}
×
1330
void SystemImpl::subscribe_param_custom(
×
1331
    const std::string& name,
1332
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1333
    const void* cookie)
1334
{
1335
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1336
}
×
1337

1338
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
28✔
1339
{
1340
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
56✔
1341

1342
    for (auto& entry : _mavlink_parameter_clients) {
30✔
1343
        if (entry.component_id == component_id && entry.extended == extended) {
21✔
1344
            return entry.parameter_client.get();
19✔
1345
        }
1346
    }
1347

1348
    _mavlink_parameter_clients.push_back(
27✔
1349
        {std::make_unique<MavlinkParameterClient>(
1350
             _mavsdk_impl.default_server_component_impl().sender(),
9✔
1351
             _mavlink_message_handler,
9✔
1352
             _mavsdk_impl.timeout_handler,
9✔
1353
             [this]() { return timeout_s(); },
47✔
1354
             [this]() { return autopilot(); },
35✔
1355
             get_system_id(),
18✔
1356
             component_id,
1357
             extended),
1358
         component_id,
1359
         extended});
1360

1361
    return _mavlink_parameter_clients.back().parameter_client.get();
9✔
1362
}
1363

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