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

mavlink / MAVSDK / 20604212380

30 Dec 2025 07:24PM UTC coverage: 48.017% (-0.06%) from 48.078%
20604212380

Pull #2746

github

web-flow
Merge 5269e5f1e into 5d2947b34
Pull Request #2746: Configuration and component cleanup

47 of 158 new or added lines in 19 files covered. (29.75%)

21 existing lines in 9 files now uncovered.

17769 of 37006 relevant lines covered (48.02%)

483.39 hits per line

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

13.37
/src/mavsdk/plugins/telemetry/telemetry_impl.cpp
1
#include "telemetry_impl.h"
2
#include "system.h"
3
#include "math_utils.h"
4
#include "callback_list.tpp"
5

6
#include <cmath>
7
#include <functional>
8
#include <string>
9
#include <array>
10
#include <cassert>
11
#include <unused.h>
12

13
namespace mavsdk {
14

15
template class CallbackList<Telemetry::PositionVelocityNed>;
16
template class CallbackList<Telemetry::Position>;
17
template class CallbackList<bool>;
18
template class CallbackList<Telemetry::StatusText>;
19
template class CallbackList<Telemetry::Quaternion>;
20
template class CallbackList<Telemetry::AngularVelocityBody>;
21
template class CallbackList<Telemetry::GroundTruth>;
22
template class CallbackList<Telemetry::FixedwingMetrics>;
23
template class CallbackList<Telemetry::EulerAngle>;
24
template class CallbackList<Telemetry::VelocityNed>;
25
template class CallbackList<Telemetry::Imu>;
26
template class CallbackList<Telemetry::GpsInfo>;
27
template class CallbackList<Telemetry::RawGps>;
28
template class CallbackList<Telemetry::Battery>;
29
template class CallbackList<Telemetry::FlightMode>;
30
template class CallbackList<Telemetry::Health>;
31
template class CallbackList<Telemetry::VtolState>;
32
template class CallbackList<Telemetry::LandedState>;
33
template class CallbackList<Telemetry::RcStatus>;
34
template class CallbackList<uint64_t>;
35
template class CallbackList<Telemetry::ActuatorControlTarget>;
36
template class CallbackList<Telemetry::ActuatorOutputStatus>;
37
template class CallbackList<Telemetry::Odometry>;
38
template class CallbackList<Telemetry::DistanceSensor>;
39
template class CallbackList<Telemetry::ScaledPressure>;
40
template class CallbackList<Telemetry::Heading>;
41
template class CallbackList<Telemetry::Altitude>;
42
template class CallbackList<Telemetry::Wind>;
43

44
TelemetryImpl::TelemetryImpl(System& system) : PluginImplBase(system)
×
45
{
46
    _system_impl->register_plugin(this);
×
47
}
×
48

49
TelemetryImpl::TelemetryImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
6✔
50
{
51
    _system_impl->register_plugin(this);
6✔
52
}
6✔
53

54
TelemetryImpl::~TelemetryImpl()
12✔
55
{
56
    _system_impl->unregister_plugin(this);
6✔
57
}
12✔
58

59
void TelemetryImpl::init()
6✔
60
{
61
    _system_impl->register_mavlink_message_handler(
6✔
62
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
63
        [this](const mavlink_message_t& message) { process_position_velocity_ned(message); },
×
64
        this);
65

66
    _system_impl->register_mavlink_message_handler(
6✔
67
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
68
        [this](const mavlink_message_t& message) { process_global_position_int(message); },
4✔
69
        this);
70

71
    _system_impl->register_mavlink_message_handler(
6✔
72
        MAVLINK_MSG_ID_HOME_POSITION,
73
        [this](const mavlink_message_t& message) { process_home_position(message); },
×
74
        this);
75

76
    _system_impl->register_mavlink_message_handler(
6✔
77
        MAVLINK_MSG_ID_ATTITUDE,
78
        [this](const mavlink_message_t& message) { process_attitude(message); },
×
79
        this);
80

81
    _system_impl->register_mavlink_message_handler(
6✔
82
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
83
        [this](const mavlink_message_t& message) { process_attitude_quaternion(message); },
×
84
        this);
85

86
    _system_impl->register_mavlink_message_handler(
6✔
87
        MAVLINK_MSG_ID_GPS_RAW_INT,
88
        [this](const mavlink_message_t& message) { process_gps_raw_int(message); },
1✔
89
        this);
90

91
    _system_impl->register_mavlink_message_handler(
6✔
92
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
93
        [this](const mavlink_message_t& message) { process_extended_sys_state(message); },
×
94
        this);
95

96
    _system_impl->register_mavlink_message_handler(
6✔
97
        MAVLINK_MSG_ID_SYS_STATUS,
98
        [this](const mavlink_message_t& message) { process_sys_status(message); },
×
99
        this);
100

101
    _system_impl->register_mavlink_message_handler(
6✔
102
        MAVLINK_MSG_ID_BATTERY_STATUS,
103
        [this](const mavlink_message_t& message) { process_battery_status(message); },
×
104
        this);
105

106
    _system_impl->register_mavlink_message_handler(
6✔
107
        MAVLINK_MSG_ID_HEARTBEAT,
108
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
3✔
109
        this);
110

111
    _system_impl->register_mavlink_message_handler(
6✔
112
        MAVLINK_MSG_ID_RC_CHANNELS,
113
        [this](const mavlink_message_t& message) { process_rc_channels(message); },
×
114
        this);
115

116
    _system_impl->register_mavlink_message_handler(
6✔
117
        MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET,
118
        [this](const mavlink_message_t& message) { process_actuator_control_target(message); },
×
119
        this);
120

121
    _system_impl->register_mavlink_message_handler(
6✔
122
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
123
        [this](const mavlink_message_t& message) { process_actuator_output_status(message); },
×
124
        this);
125

126
    _system_impl->register_mavlink_message_handler(
6✔
127
        MAVLINK_MSG_ID_ODOMETRY,
128
        [this](const mavlink_message_t& message) { process_odometry(message); },
×
129
        this);
130

131
    _system_impl->register_mavlink_message_handler(
6✔
132
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
133
        [this](const mavlink_message_t& message) { process_distance_sensor(message); },
×
134
        this);
135

136
    _system_impl->register_mavlink_message_handler(
6✔
137
        MAVLINK_MSG_ID_SCALED_PRESSURE,
138
        [this](const mavlink_message_t& message) { process_scaled_pressure(message); },
×
139
        this);
140

141
    _system_impl->register_mavlink_message_handler(
6✔
142
        MAVLINK_MSG_ID_SYSTEM_TIME,
143
        [this](const mavlink_message_t& message) { process_unix_epoch_time(message); },
×
144
        this);
145

146
    _system_impl->register_mavlink_message_handler(
6✔
147
        MAVLINK_MSG_ID_HIGHRES_IMU,
148
        [this](const mavlink_message_t& message) { process_imu_reading_ned(message); },
×
149
        this);
150

151
    _system_impl->register_mavlink_message_handler(
6✔
152
        MAVLINK_MSG_ID_SCALED_IMU,
153
        [this](const mavlink_message_t& message) { process_scaled_imu(message); },
×
154
        this);
155

156
    _system_impl->register_mavlink_message_handler(
6✔
157
        MAVLINK_MSG_ID_RAW_IMU,
158
        [this](const mavlink_message_t& message) { process_raw_imu(message); },
×
159
        this);
160

161
    _system_impl->register_mavlink_message_handler(
6✔
162
        MAVLINK_MSG_ID_VFR_HUD,
163
        [this](const mavlink_message_t& message) { process_fixedwing_metrics(message); },
×
164
        this);
165

166
    _system_impl->register_mavlink_message_handler(
6✔
167
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
168
        [this](const mavlink_message_t& message) { process_ground_truth(message); },
×
169
        this);
170

171
    _system_impl->register_mavlink_message_handler(
6✔
172
        MAVLINK_MSG_ID_ALTITUDE,
173
        [this](const mavlink_message_t& message) { process_altitude(message); },
×
174
        this);
175

176
    _system_impl->register_mavlink_message_handler(
6✔
177
        MAVLINK_MSG_ID_WIND_COV,
178
        [this](const mavlink_message_t& message) { process_wind(message); },
×
179
        this);
180

181
    _system_impl->register_statustext_handler(
6✔
182
        [this](const MavlinkStatustextHandler::Statustext& statustext) {
3✔
183
            receive_statustext(statustext);
3✔
184
        },
3✔
185
        this);
186
}
6✔
187

188
void TelemetryImpl::deinit()
6✔
189
{
190
    _system_impl->unregister_statustext_handler(this);
6✔
191
    // Use blocking version to ensure any in-flight callbacks complete before destruction.
192
    _system_impl->unregister_all_mavlink_message_handlers_blocking(this);
6✔
193
}
6✔
194

195
void TelemetryImpl::enable()
6✔
196
{
197
    // We're going to retry until we have the Home Position.
198
    _homepos_cookie =
6✔
199
        _system_impl->add_call_every([this]() { request_home_position_again(); }, 2.0f);
12✔
200
}
6✔
201

202
void TelemetryImpl::disable()
6✔
203
{
204
    _system_impl->remove_call_every(_homepos_cookie);
6✔
205
    {
206
        std::lock_guard<std::mutex> lock(_health_mutex);
6✔
207
        _health.is_home_position_ok = false;
6✔
208
    }
6✔
209

210
    // FIXME: this is a race condition where request_home_position_again
211
    //        could still be executing after we have removed it.
212
    std::this_thread::sleep_for(std::chrono::milliseconds(200));
6✔
213
}
6✔
214

215
void TelemetryImpl::request_home_position_again()
6✔
216
{
217
    {
218
        std::lock_guard<std::mutex> lock(_health_mutex);
6✔
219
        if (_health.is_home_position_ok) {
6✔
220
            _system_impl->remove_call_every(_homepos_cookie);
×
221
            return;
×
222
        }
223

224
        _system_impl->mavlink_request_message().request(
6✔
225
            MAVLINK_MSG_ID_HOME_POSITION, MAV_COMP_ID_AUTOPILOT1, nullptr);
226
    }
6✔
227
}
228

229
Telemetry::Result TelemetryImpl::set_rate_position_velocity_ned(double rate_hz)
×
230
{
231
    return telemetry_result_from_command_result(
×
232
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_LOCAL_POSITION_NED, rate_hz));
×
233
}
234

235
Telemetry::Result TelemetryImpl::set_rate_position(double rate_hz)
×
236
{
237
    _position_rate_hz = rate_hz;
×
238
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
239

240
    return telemetry_result_from_command_result(
×
241
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
242
}
243

244
Telemetry::Result TelemetryImpl::set_rate_home(double rate_hz)
×
245
{
246
    return telemetry_result_from_command_result(
×
247
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HOME_POSITION, rate_hz));
×
248
}
249

250
Telemetry::Result TelemetryImpl::set_rate_in_air(double rate_hz)
×
251
{
252
    return set_rate_landed_state(rate_hz);
×
253
}
254

255
Telemetry::Result TelemetryImpl::set_rate_vtol_state(double rate_hz)
×
256
{
257
    return set_rate_landed_state(rate_hz);
×
258
}
259

260
Telemetry::Result TelemetryImpl::set_rate_landed_state(double rate_hz)
×
261
{
262
    return telemetry_result_from_command_result(
×
263
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_EXTENDED_SYS_STATE, rate_hz));
×
264
}
265

266
Telemetry::Result TelemetryImpl::set_rate_attitude_quaternion(double rate_hz)
×
267
{
268
    return telemetry_result_from_command_result(
×
269
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE_QUATERNION, rate_hz));
×
270
}
271

272
Telemetry::Result TelemetryImpl::set_rate_attitude_euler(double rate_hz)
×
273
{
274
    return telemetry_result_from_command_result(
×
275
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE, rate_hz));
×
276
}
277

278
Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz)
×
279
{
280
    _velocity_ned_rate_hz = rate_hz;
×
281
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
282

283
    return telemetry_result_from_command_result(
×
284
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
285
}
286

287
Telemetry::Result TelemetryImpl::set_rate_imu(double rate_hz)
×
288
{
289
    return telemetry_result_from_command_result(
×
290
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIGHRES_IMU, rate_hz));
×
291
}
292

293
Telemetry::Result TelemetryImpl::set_rate_scaled_imu(double rate_hz)
×
294
{
295
    return telemetry_result_from_command_result(
×
296
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SCALED_IMU, rate_hz));
×
297
}
298

299
Telemetry::Result TelemetryImpl::set_rate_raw_imu(double rate_hz)
×
300
{
301
    return telemetry_result_from_command_result(
×
302
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_RAW_IMU, rate_hz));
×
303
}
304

305
Telemetry::Result TelemetryImpl::set_rate_fixedwing_metrics(double rate_hz)
×
306
{
307
    return telemetry_result_from_command_result(
×
308
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_VFR_HUD, rate_hz));
×
309
}
310

311
Telemetry::Result TelemetryImpl::set_rate_ground_truth(double rate_hz)
×
312
{
313
    return telemetry_result_from_command_result(
×
314
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIL_STATE_QUATERNION, rate_hz));
×
315
}
316

317
Telemetry::Result TelemetryImpl::set_rate_gps_info(double rate_hz)
×
318
{
319
    return telemetry_result_from_command_result(
×
320
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GPS_RAW_INT, rate_hz));
×
321
}
322

323
Telemetry::Result TelemetryImpl::set_rate_battery(double rate_hz)
×
324
{
325
    return telemetry_result_from_command_result(
×
326
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_BATTERY_STATUS, rate_hz));
×
327
}
328

329
Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz)
×
330
{
331
    UNUSED(rate_hz);
×
332
    LogWarn() << "System status is usually fixed at 1 Hz";
×
333
    return Telemetry::Result::Unsupported;
×
334
}
335

336
Telemetry::Result TelemetryImpl::set_rate_actuator_control_target(double rate_hz)
×
337
{
338
    return telemetry_result_from_command_result(
×
339
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, rate_hz));
×
340
}
341

342
Telemetry::Result TelemetryImpl::set_rate_actuator_output_status(double rate_hz)
×
343
{
344
    return telemetry_result_from_command_result(
×
345
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, rate_hz));
×
346
}
347

348
Telemetry::Result TelemetryImpl::set_rate_odometry(double rate_hz)
×
349
{
350
    return telemetry_result_from_command_result(
×
351
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ODOMETRY, rate_hz));
×
352
}
353

354
Telemetry::Result TelemetryImpl::set_rate_distance_sensor(double rate_hz)
×
355
{
356
    return telemetry_result_from_command_result(
×
357
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_DISTANCE_SENSOR, rate_hz));
×
358
}
359

360
Telemetry::Result TelemetryImpl::set_rate_scaled_pressure(double rate_hz)
×
361
{
362
    return telemetry_result_from_command_result(
×
363
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SCALED_PRESSURE, rate_hz));
×
364
}
365

366
Telemetry::Result TelemetryImpl::set_rate_unix_epoch_time(double rate_hz)
×
367
{
368
    return telemetry_result_from_command_result(
×
369
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SYSTEM_TIME, rate_hz));
×
370
}
371

372
Telemetry::Result TelemetryImpl::set_rate_altitude(double rate_hz)
×
373
{
374
    return telemetry_result_from_command_result(
×
375
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ALTITUDE, rate_hz));
×
376
}
377

378
Telemetry::Result TelemetryImpl::set_rate_health(double rate_hz)
×
379
{
380
    return telemetry_result_from_command_result(
×
381
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SYS_STATUS, rate_hz));
×
382
}
383

384
void TelemetryImpl::set_rate_position_velocity_ned_async(
×
385
    double rate_hz, Telemetry::ResultCallback callback)
386
{
387
    _system_impl->set_msg_rate_async(
×
388
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
389
        rate_hz,
390
        [callback](MavlinkCommandSender::Result command_result, float) {
×
391
            command_result_callback(command_result, callback);
×
392
        });
×
393
}
×
394

395
void TelemetryImpl::set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
396
{
397
    _position_rate_hz = rate_hz;
×
398
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
399

400
    _system_impl->set_msg_rate_async(
×
401
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
402
        max_rate_hz,
403
        [callback](MavlinkCommandSender::Result command_result, float) {
×
404
            command_result_callback(command_result, callback);
×
405
        });
×
406
}
×
407

408
void TelemetryImpl::set_rate_home_async(double rate_hz, Telemetry::ResultCallback callback)
×
409
{
410
    _system_impl->set_msg_rate_async(
×
411
        MAVLINK_MSG_ID_HOME_POSITION,
412
        rate_hz,
413
        [callback](MavlinkCommandSender::Result command_result, float) {
×
414
            command_result_callback(command_result, callback);
×
415
        });
×
416
}
×
417

418
void TelemetryImpl::set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
419
{
420
    set_rate_landed_state_async(rate_hz, callback);
×
421
}
×
422

423
void TelemetryImpl::set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
424
{
425
    set_rate_landed_state_async(rate_hz, callback);
×
426
}
×
427

428
void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
429
{
430
    _system_impl->set_msg_rate_async(
×
431
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
432
        rate_hz,
433
        [callback](MavlinkCommandSender::Result command_result, float) {
×
434
            command_result_callback(command_result, callback);
×
435
        });
×
436
}
×
437

438
void TelemetryImpl::set_rate_altitude_async(double rate_hz, Telemetry::ResultCallback callback)
×
439
{
440
    _system_impl->set_msg_rate_async(
×
441
        MAVLINK_MSG_ID_ALTITUDE,
442
        rate_hz,
443
        [callback](MavlinkCommandSender::Result command_result, float) {
×
444
            command_result_callback(command_result, callback);
×
445
        });
×
446
}
×
447

448
void TelemetryImpl::set_rate_health_async(double rate_hz, Telemetry::ResultCallback callback)
×
449
{
450
    _system_impl->set_msg_rate_async(
×
451
        MAVLINK_MSG_ID_SYS_STATUS,
452
        rate_hz,
453
        [callback](MavlinkCommandSender::Result command_result, float) {
×
454
            command_result_callback(command_result, callback);
×
455
        });
×
456
}
×
457

458
void TelemetryImpl::set_rate_attitude_quaternion_async(
×
459
    double rate_hz, Telemetry::ResultCallback callback)
460
{
461
    _system_impl->set_msg_rate_async(
×
462
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
463
        rate_hz,
464
        [callback](MavlinkCommandSender::Result command_result, float) {
×
465
            command_result_callback(command_result, callback);
×
466
        });
×
467
}
×
468

469
void TelemetryImpl::set_rate_attitude_euler_async(
×
470
    double rate_hz, Telemetry::ResultCallback callback)
471
{
472
    _system_impl->set_msg_rate_async(
×
473
        MAVLINK_MSG_ID_ATTITUDE,
474
        rate_hz,
475
        [callback](MavlinkCommandSender::Result command_result, float) {
×
476
            command_result_callback(command_result, callback);
×
477
        });
×
478
}
×
479

480
void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
481
{
482
    _velocity_ned_rate_hz = rate_hz;
×
483
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
484

485
    _system_impl->set_msg_rate_async(
×
486
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
487
        max_rate_hz,
488
        [callback](MavlinkCommandSender::Result command_result, float) {
×
489
            command_result_callback(command_result, callback);
×
490
        });
×
491
}
×
492

493
void TelemetryImpl::set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
494
{
495
    _system_impl->set_msg_rate_async(
×
496
        MAVLINK_MSG_ID_HIGHRES_IMU,
497
        rate_hz,
498
        [callback](MavlinkCommandSender::Result command_result, float) {
×
499
            command_result_callback(command_result, callback);
×
500
        });
×
501
}
×
502

503
void TelemetryImpl::set_rate_scaled_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
504
{
505
    _system_impl->set_msg_rate_async(
×
506
        MAVLINK_MSG_ID_SCALED_IMU,
507
        rate_hz,
508
        [callback](MavlinkCommandSender::Result command_result, float) {
×
509
            command_result_callback(command_result, callback);
×
510
        });
×
511
}
×
512

513
void TelemetryImpl::set_rate_raw_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
514
{
515
    _system_impl->set_msg_rate_async(
×
516
        MAVLINK_MSG_ID_RAW_IMU,
517
        rate_hz,
518
        [callback](MavlinkCommandSender::Result command_result, float) {
×
519
            command_result_callback(command_result, callback);
×
520
        });
×
521
}
×
522

523
void TelemetryImpl::set_rate_fixedwing_metrics_async(
×
524
    double rate_hz, Telemetry::ResultCallback callback)
525
{
526
    _system_impl->set_msg_rate_async(
×
527
        MAVLINK_MSG_ID_VFR_HUD,
528
        rate_hz,
529
        [callback](MavlinkCommandSender::Result command_result, float) {
×
530
            command_result_callback(command_result, callback);
×
531
        });
×
532
}
×
533

534
void TelemetryImpl::set_rate_ground_truth_async(double rate_hz, Telemetry::ResultCallback callback)
×
535
{
536
    _system_impl->set_msg_rate_async(
×
537
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
538
        rate_hz,
539
        [callback](MavlinkCommandSender::Result command_result, float) {
×
540
            command_result_callback(command_result, callback);
×
541
        });
×
542
}
×
543

544
void TelemetryImpl::set_rate_gps_info_async(double rate_hz, Telemetry::ResultCallback callback)
×
545
{
546
    _system_impl->set_msg_rate_async(
×
547
        MAVLINK_MSG_ID_GPS_RAW_INT,
548
        rate_hz,
549
        [callback](MavlinkCommandSender::Result command_result, float) {
×
550
            command_result_callback(command_result, callback);
×
551
        });
×
552
}
×
553

554
void TelemetryImpl::set_rate_battery_async(double rate_hz, Telemetry::ResultCallback callback)
×
555
{
556
    _system_impl->set_msg_rate_async(
×
557
        MAVLINK_MSG_ID_BATTERY_STATUS,
558
        rate_hz,
559
        [callback](MavlinkCommandSender::Result command_result, float) {
×
560
            command_result_callback(command_result, callback);
×
561
        });
×
562
}
×
563

564
void TelemetryImpl::set_rate_rc_status_async(double rate_hz, Telemetry::ResultCallback callback)
×
565
{
566
    UNUSED(rate_hz);
×
567
    LogWarn() << "System status is usually fixed at 1 Hz";
×
568
    _system_impl->call_user_callback([callback]() { callback(Telemetry::Result::Unsupported); });
×
569
}
×
570

571
void TelemetryImpl::set_rate_unix_epoch_time_async(
×
572
    double rate_hz, Telemetry::ResultCallback callback)
573
{
574
    _system_impl->set_msg_rate_async(
×
575
        MAVLINK_MSG_ID_SYSTEM_TIME,
576
        rate_hz,
577
        [callback](MavlinkCommandSender::Result command_result, float) {
×
578
            command_result_callback(command_result, callback);
×
579
        });
×
580
}
×
581

582
void TelemetryImpl::set_rate_actuator_control_target_async(
×
583
    double rate_hz, Telemetry::ResultCallback callback)
584
{
585
    _system_impl->set_msg_rate_async(
×
586
        MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET,
587
        rate_hz,
588
        [callback](MavlinkCommandSender::Result command_result, float) {
×
589
            command_result_callback(command_result, callback);
×
590
        });
×
591
}
×
592

593
void TelemetryImpl::set_rate_actuator_output_status_async(
×
594
    double rate_hz, Telemetry::ResultCallback callback)
595
{
596
    _system_impl->set_msg_rate_async(
×
597
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
598
        rate_hz,
599
        [callback](MavlinkCommandSender::Result command_result, float) {
×
600
            command_result_callback(command_result, callback);
×
601
        });
×
602
}
×
603

604
void TelemetryImpl::set_rate_odometry_async(double rate_hz, Telemetry::ResultCallback callback)
×
605
{
606
    _system_impl->set_msg_rate_async(
×
607
        MAVLINK_MSG_ID_ODOMETRY,
608
        rate_hz,
609
        [callback](MavlinkCommandSender::Result command_result, float) {
×
610
            command_result_callback(command_result, callback);
×
611
        });
×
612
}
×
613

614
void TelemetryImpl::set_rate_distance_sensor_async(
×
615
    double rate_hz, Telemetry::ResultCallback callback)
616
{
617
    _system_impl->set_msg_rate_async(
×
618
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
619
        rate_hz,
620
        [callback](MavlinkCommandSender::Result command_result, float) {
×
621
            command_result_callback(command_result, callback);
×
622
        });
×
623
}
×
624

625
void TelemetryImpl::set_rate_scaled_pressure_async(
×
626
    double rate_hz, Telemetry::ResultCallback callback)
627
{
628
    _system_impl->set_msg_rate_async(
×
629
        MAVLINK_MSG_ID_SCALED_PRESSURE,
630
        rate_hz,
631
        [callback](MavlinkCommandSender::Result command_result, float) {
×
632
            command_result_callback(command_result, callback);
×
633
        });
×
634
}
×
635

636
Telemetry::Result
637
TelemetryImpl::telemetry_result_from_command_result(MavlinkCommandSender::Result command_result)
×
638
{
639
    switch (command_result) {
×
640
        case MavlinkCommandSender::Result::Success:
×
641
            return Telemetry::Result::Success;
×
642
        case MavlinkCommandSender::Result::NoSystem:
×
643
            return Telemetry::Result::NoSystem;
×
644
        case MavlinkCommandSender::Result::ConnectionError:
×
645
            return Telemetry::Result::ConnectionError;
×
646
        case MavlinkCommandSender::Result::Busy:
×
647
            return Telemetry::Result::Busy;
×
648
        case MavlinkCommandSender::Result::Denied:
×
649
            // FALLTHROUGH
650
        case MavlinkCommandSender::Result::TemporarilyRejected:
651
            return Telemetry::Result::CommandDenied;
×
652
        case MavlinkCommandSender::Result::Timeout:
×
653
            return Telemetry::Result::Timeout;
×
654
        case MavlinkCommandSender::Result::Unsupported:
×
655
            return Telemetry::Result::Unsupported;
×
656
        default:
×
657
            return Telemetry::Result::Unknown;
×
658
    }
659
}
660

661
void TelemetryImpl::command_result_callback(
×
662
    MavlinkCommandSender::Result command_result, const Telemetry::ResultCallback& callback)
663
{
664
    Telemetry::Result action_result = telemetry_result_from_command_result(command_result);
×
665

666
    callback(action_result);
×
667
}
×
668

669
void TelemetryImpl::process_position_velocity_ned(const mavlink_message_t& message)
×
670
{
671
    mavlink_local_position_ned_t local_position;
672
    mavlink_msg_local_position_ned_decode(&message, &local_position);
×
673

674
    Telemetry::PositionVelocityNed position_velocity;
×
675
    position_velocity.position.north_m = local_position.x;
×
676
    position_velocity.position.east_m = local_position.y;
×
677
    position_velocity.position.down_m = local_position.z;
×
678
    position_velocity.velocity.north_m_s = local_position.vx;
×
679
    position_velocity.velocity.east_m_s = local_position.vy;
×
680
    position_velocity.velocity.down_m_s = local_position.vz;
×
681

682
    set_position_velocity_ned(position_velocity);
×
683

684
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
685
    _position_velocity_ned_subscriptions.queue(position_velocity_ned(), [this](const auto& func) {
×
686
        _system_impl->call_user_callback(func);
×
687
    });
×
688

689
    set_health_local_position(true);
×
690
}
×
691

692
void TelemetryImpl::process_global_position_int(const mavlink_message_t& message)
4✔
693
{
694
    mavlink_global_position_int_t global_position_int;
695
    mavlink_msg_global_position_int_decode(&message, &global_position_int);
4✔
696

697
    {
698
        Telemetry::Position position;
4✔
699
        position.latitude_deg = global_position_int.lat * 1e-7;
4✔
700
        position.longitude_deg = global_position_int.lon * 1e-7;
4✔
701
        position.absolute_altitude_m = global_position_int.alt * 1e-3f;
4✔
702
        position.relative_altitude_m = global_position_int.relative_alt * 1e-3f;
4✔
703
        set_position(position);
4✔
704
    }
705

706
    {
707
        Telemetry::VelocityNed velocity;
4✔
708
        velocity.north_m_s = global_position_int.vx * 1e-2f;
4✔
709
        velocity.east_m_s = global_position_int.vy * 1e-2f;
4✔
710
        velocity.down_m_s = global_position_int.vz * 1e-2f;
4✔
711
        set_velocity_ned(velocity);
4✔
712
    }
713

714
    {
715
        Telemetry::Heading heading;
4✔
716
        heading.heading_deg = (global_position_int.hdg != std::numeric_limits<uint16_t>::max()) ?
4✔
717
                                  static_cast<double>(global_position_int.hdg) * 1e-2 :
4✔
718
                                  static_cast<double>(NAN);
719
        set_heading(heading);
4✔
720
    }
721

722
    std::lock_guard<std::mutex> lock(_subscription_mutex);
4✔
723
    _position_subscriptions.queue(
4✔
724
        position(), [this](const auto& func) { _system_impl->call_user_callback(func); });
3✔
725

726
    _velocity_ned_subscriptions.queue(
4✔
727
        velocity_ned(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
728

729
    _heading_subscriptions.queue(
4✔
730
        heading(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
731
}
4✔
732

733
void TelemetryImpl::process_home_position(const mavlink_message_t& message)
×
734
{
735
    mavlink_home_position_t home_position;
736
    mavlink_msg_home_position_decode(&message, &home_position);
×
737
    Telemetry::Position new_pos;
×
738
    new_pos.latitude_deg = home_position.latitude * 1e-7;
×
739
    new_pos.longitude_deg = home_position.longitude * 1e-7;
×
740
    new_pos.absolute_altitude_m = home_position.altitude * 1e-3f;
×
741
    new_pos.relative_altitude_m = 0.0f; // 0 by definition.
×
742

743
    set_home_position(new_pos);
×
744

745
    set_health_home_position(true);
×
746

747
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
748
    _home_position_subscriptions.queue(
×
749
        home(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
750
}
×
751

752
void TelemetryImpl::process_attitude(const mavlink_message_t& message)
×
753
{
754
    mavlink_attitude_t attitude;
755
    mavlink_msg_attitude_decode(&message, &attitude);
×
756

757
    Telemetry::EulerAngle euler_angle;
×
758
    euler_angle.roll_deg = to_deg_from_rad(attitude.roll);
×
759
    euler_angle.pitch_deg = to_deg_from_rad(attitude.pitch);
×
760
    euler_angle.yaw_deg = to_deg_from_rad(attitude.yaw);
×
761
    euler_angle.timestamp_us = static_cast<uint64_t>(attitude.time_boot_ms) * 1000;
×
762
    set_attitude_euler(euler_angle);
×
763

764
    Telemetry::AngularVelocityBody angular_velocity_body;
×
765
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
766
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
767
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
768
    set_attitude_angular_velocity_body(angular_velocity_body);
×
769

770
    _attitude_euler_angle_subscriptions.queue(
×
771
        attitude_euler(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
772

773
    _attitude_angular_velocity_body_subscriptions.queue(
×
774
        attitude_angular_velocity_body(),
775
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
776
}
×
777

778
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
779
{
780
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
781
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
782

783
    Telemetry::Quaternion quaternion;
×
784
    quaternion.w = mavlink_attitude_quaternion.q1;
×
785
    quaternion.x = mavlink_attitude_quaternion.q2;
×
786
    quaternion.y = mavlink_attitude_quaternion.q3;
×
787
    quaternion.z = mavlink_attitude_quaternion.q4;
×
788
    quaternion.timestamp_us =
×
789
        static_cast<uint64_t>(mavlink_attitude_quaternion.time_boot_ms) * 1000;
×
790

791
    Telemetry::AngularVelocityBody angular_velocity_body;
×
792
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
793
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
794
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
795

796
    set_attitude_quaternion(quaternion);
×
797

798
    set_attitude_angular_velocity_body(angular_velocity_body);
×
799

800
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
801
    _attitude_quaternion_angle_subscriptions.queue(attitude_quaternion(), [this](const auto& func) {
×
802
        _system_impl->call_user_callback(func);
×
803
    });
×
804

805
    _attitude_angular_velocity_body_subscriptions.queue(
×
806
        attitude_angular_velocity_body(),
807
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
808
}
×
809

810
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
811
{
812
    mavlink_altitude_t mavlink_altitude;
813
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
814

815
    Telemetry::Altitude new_altitude;
×
816
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
817
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
818
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
819
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
820
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
821
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
822

823
    set_altitude(new_altitude);
×
824

825
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
826
    _altitude_subscriptions.queue(
×
827
        altitude(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
828
}
×
829

830
void TelemetryImpl::process_wind(const mavlink_message_t& message)
×
831
{
832
    __mavlink_wind_cov_t mavlink_wind_cov;
833
    mavlink_msg_wind_cov_decode(&message, &mavlink_wind_cov);
×
834

835
    Telemetry::Wind new_wind;
×
836
    new_wind.wind_x_ned_m_s = mavlink_wind_cov.wind_x;
×
837
    new_wind.wind_y_ned_m_s = mavlink_wind_cov.wind_y;
×
838
    new_wind.wind_z_ned_m_s = mavlink_wind_cov.wind_z;
×
839
    new_wind.horizontal_variability_stddev_m_s = mavlink_wind_cov.var_horiz;
×
840
    new_wind.vertical_variability_stddev_m_s = mavlink_wind_cov.var_vert;
×
841
    new_wind.wind_altitude_msl_m = mavlink_wind_cov.wind_alt;
×
842
    new_wind.horizontal_wind_speed_accuracy_m_s = mavlink_wind_cov.horiz_accuracy;
×
843
    new_wind.vertical_wind_speed_accuracy_m_s = mavlink_wind_cov.vert_accuracy;
×
844

845
    set_wind(new_wind);
×
846

847
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
848
    _wind_subscriptions.queue(
×
849
        wind(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
850
}
×
851

852
void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message)
×
853
{
854
    mavlink_highres_imu_t highres_imu;
855
    mavlink_msg_highres_imu_decode(&message, &highres_imu);
×
856
    Telemetry::Imu new_imu;
×
857
    new_imu.acceleration_frd.forward_m_s2 = highres_imu.xacc;
×
858
    new_imu.acceleration_frd.right_m_s2 = highres_imu.yacc;
×
859
    new_imu.acceleration_frd.down_m_s2 = highres_imu.zacc;
×
860
    new_imu.angular_velocity_frd.forward_rad_s = highres_imu.xgyro;
×
861
    new_imu.angular_velocity_frd.right_rad_s = highres_imu.ygyro;
×
862
    new_imu.angular_velocity_frd.down_rad_s = highres_imu.zgyro;
×
863
    new_imu.magnetic_field_frd.forward_gauss = highres_imu.xmag;
×
864
    new_imu.magnetic_field_frd.right_gauss = highres_imu.ymag;
×
865
    new_imu.magnetic_field_frd.down_gauss = highres_imu.zmag;
×
866
    new_imu.temperature_degc = highres_imu.temperature;
×
867
    new_imu.timestamp_us = highres_imu.time_usec;
×
868

869
    set_imu_reading_ned(new_imu);
×
870

871
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
872
    _imu_reading_ned_subscriptions.queue(
×
873
        imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
874
}
×
875

876
void TelemetryImpl::process_scaled_imu(const mavlink_message_t& message)
×
877
{
878
    mavlink_scaled_imu_t scaled_imu_reading;
879
    mavlink_msg_scaled_imu_decode(&message, &scaled_imu_reading);
×
880
    Telemetry::Imu new_imu;
×
881
    // From mG to m/s^2
882
    new_imu.acceleration_frd.forward_m_s2 = scaled_imu_reading.xacc / 1000.f * 9.81f;
×
883
    new_imu.acceleration_frd.right_m_s2 = scaled_imu_reading.yacc / 1000.f * 9.81f;
×
884
    new_imu.acceleration_frd.down_m_s2 = scaled_imu_reading.zacc / 1000.f * 9.81f;
×
885
    // From mrad to rad
886
    new_imu.angular_velocity_frd.forward_rad_s = scaled_imu_reading.xgyro / 1000.f;
×
887
    new_imu.angular_velocity_frd.right_rad_s = scaled_imu_reading.ygyro / 1000.f;
×
888
    new_imu.angular_velocity_frd.down_rad_s = scaled_imu_reading.zgyro / 1000.f;
×
889
    // From milliGauss to Gauss
890
    new_imu.magnetic_field_frd.forward_gauss = scaled_imu_reading.xmag / 1000.f;
×
891
    new_imu.magnetic_field_frd.right_gauss = scaled_imu_reading.ymag / 1000.f;
×
892
    new_imu.magnetic_field_frd.down_gauss = scaled_imu_reading.zmag / 1000.f;
×
893
    new_imu.temperature_degc = static_cast<float>(scaled_imu_reading.temperature) * 1e-2f;
×
894
    new_imu.timestamp_us = static_cast<uint64_t>(scaled_imu_reading.time_boot_ms) * 1000;
×
895

896
    set_scaled_imu(new_imu);
×
897

898
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
899
    _scaled_imu_subscriptions.queue(
×
900
        scaled_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
901
}
×
902

903
void TelemetryImpl::process_raw_imu(const mavlink_message_t& message)
×
904
{
905
    mavlink_raw_imu_t raw_imu_reading;
906
    mavlink_msg_raw_imu_decode(&message, &raw_imu_reading);
×
907
    Telemetry::Imu new_imu;
×
908
    new_imu.acceleration_frd.forward_m_s2 = raw_imu_reading.xacc;
×
909
    new_imu.acceleration_frd.right_m_s2 = raw_imu_reading.yacc;
×
910
    new_imu.acceleration_frd.down_m_s2 = raw_imu_reading.zacc;
×
911
    new_imu.angular_velocity_frd.forward_rad_s = raw_imu_reading.xgyro;
×
912
    new_imu.angular_velocity_frd.right_rad_s = raw_imu_reading.ygyro;
×
913
    new_imu.angular_velocity_frd.down_rad_s = raw_imu_reading.zgyro;
×
914
    new_imu.magnetic_field_frd.forward_gauss = raw_imu_reading.xmag;
×
915
    new_imu.magnetic_field_frd.right_gauss = raw_imu_reading.ymag;
×
916
    new_imu.magnetic_field_frd.down_gauss = raw_imu_reading.zmag;
×
917
    new_imu.temperature_degc = static_cast<float>(raw_imu_reading.temperature) * 1e-2f;
×
918
    new_imu.timestamp_us = raw_imu_reading.time_usec;
×
919

920
    set_raw_imu(new_imu);
×
921

922
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
923
    _raw_imu_subscriptions.queue(
×
924
        raw_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
925
}
×
926

927
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
1✔
928
{
929
    mavlink_gps_raw_int_t gps_raw_int;
930
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
1✔
931

932
    Telemetry::FixType fix_type;
933
    switch (gps_raw_int.fix_type) {
1✔
934
        case 0:
×
935
            fix_type = Telemetry::FixType::NoGps;
×
936
            break;
×
937
        case 1:
×
938
            fix_type = Telemetry::FixType::NoFix;
×
939
            break;
×
940
        case 2:
×
941
            fix_type = Telemetry::FixType::Fix2D;
×
942
            break;
×
943
        case 3:
1✔
944
            fix_type = Telemetry::FixType::Fix3D;
1✔
945
            break;
1✔
946
        case 4:
×
947
            fix_type = Telemetry::FixType::FixDgps;
×
948
            break;
×
949
        case 5:
×
950
            fix_type = Telemetry::FixType::RtkFloat;
×
951
            break;
×
952
        case 6:
×
953
            fix_type = Telemetry::FixType::RtkFixed;
×
954
            break;
×
955

956
        default:
×
957
            LogErr() << "Received unknown GPS fix type!";
×
958
            fix_type = Telemetry::FixType::NoGps;
×
959
            break;
×
960
    }
961

962
    Telemetry::GpsInfo new_gps_info;
1✔
963
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
1✔
964
    new_gps_info.fix_type = fix_type;
1✔
965
    set_gps_info(new_gps_info);
1✔
966

967
    Telemetry::RawGps raw_gps_info;
1✔
968
    raw_gps_info.timestamp_us = gps_raw_int.time_usec;
1✔
969
    raw_gps_info.latitude_deg = gps_raw_int.lat * 1e-7;
1✔
970
    raw_gps_info.longitude_deg = gps_raw_int.lon * 1e-7;
1✔
971
    raw_gps_info.absolute_altitude_m = gps_raw_int.alt * 1e-3f;
1✔
972
    raw_gps_info.hdop = static_cast<float>(gps_raw_int.eph) * 1e-2f;
1✔
973
    raw_gps_info.vdop = static_cast<float>(gps_raw_int.epv) * 1e-2f;
1✔
974
    raw_gps_info.velocity_m_s = static_cast<float>(gps_raw_int.vel) * 1e-2f;
1✔
975
    raw_gps_info.cog_deg = static_cast<float>(gps_raw_int.cog) * 1e-2f;
1✔
976
    raw_gps_info.altitude_ellipsoid_m = static_cast<float>(gps_raw_int.alt_ellipsoid) * 1e-3f;
1✔
977
    raw_gps_info.horizontal_uncertainty_m = static_cast<float>(gps_raw_int.h_acc) * 1e-3f;
1✔
978
    raw_gps_info.vertical_uncertainty_m = static_cast<float>(gps_raw_int.v_acc) * 1e-3f;
1✔
979
    raw_gps_info.velocity_uncertainty_m_s = static_cast<float>(gps_raw_int.vel_acc) * 1e-3f;
1✔
980
    raw_gps_info.heading_uncertainty_deg = static_cast<float>(gps_raw_int.hdg_acc) * 1e-5f;
1✔
981
    raw_gps_info.yaw_deg = static_cast<float>(gps_raw_int.yaw) * 1e-2f;
1✔
982
    set_raw_gps(raw_gps_info);
1✔
983

984
    {
985
        std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
986
        _gps_info_subscriptions.queue(
1✔
987
            gps_info(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
988
        _raw_gps_subscriptions.queue(
1✔
989
            raw_gps(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
990
    }
1✔
991
}
1✔
992

993
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
994
{
995
    mavlink_hil_state_quaternion_t hil_state_quaternion;
996
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
997

998
    Telemetry::GroundTruth new_ground_truth;
×
999
    new_ground_truth.latitude_deg = hil_state_quaternion.lat * 1e-7;
×
1000
    new_ground_truth.longitude_deg = hil_state_quaternion.lon * 1e-7;
×
1001
    new_ground_truth.absolute_altitude_m = hil_state_quaternion.alt * 1e-3f;
×
1002

1003
    set_ground_truth(new_ground_truth);
×
1004

1005
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1006
    _ground_truth_subscriptions.queue(
×
1007
        ground_truth(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1008
}
×
1009

1010
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
1011
{
1012
    mavlink_extended_sys_state_t extended_sys_state;
1013
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
1014

1015
    {
1016
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
1017
        set_landed_state(landed_state);
×
1018

1019
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
1020
        set_vtol_state(vtol_state);
×
1021
    }
1022

1023
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1024
    _landed_state_subscriptions.queue(
×
1025
        landed_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1026

1027
    _vtol_state_subscriptions.queue(
×
1028
        vtol_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1029

1030
    if (extended_sys_state.landed_state == MAV_LANDED_STATE_IN_AIR ||
×
1031
        extended_sys_state.landed_state == MAV_LANDED_STATE_TAKEOFF ||
×
1032
        extended_sys_state.landed_state == MAV_LANDED_STATE_LANDING) {
×
1033
        set_in_air(true);
×
1034
    } else if (extended_sys_state.landed_state == MAV_LANDED_STATE_ON_GROUND) {
×
1035
        set_in_air(false);
×
1036
    }
1037
    // If landed_state is undefined, we use what we have received last.
1038

1039
    _in_air_subscriptions.queue(
×
1040
        in_air(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1041
}
×
1042
void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)
×
1043
{
1044
    mavlink_vfr_hud_t vfr_hud;
1045
    mavlink_msg_vfr_hud_decode(&message, &vfr_hud);
×
1046

1047
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
1048
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
1049
    new_fixedwing_metrics.groundspeed_m_s = vfr_hud.groundspeed;
×
1050
    new_fixedwing_metrics.heading_deg = vfr_hud.heading;
×
1051
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
1052
    new_fixedwing_metrics.absolute_altitude_m = vfr_hud.alt;
×
1053
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1054

1055
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1056

1057
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1058
    _fixedwing_metrics_subscriptions.queue(
×
1059
        fixedwing_metrics(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1060
}
×
1061

1062
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1063
{
1064
    mavlink_sys_status_t sys_status;
1065
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1066

1067
    if (!_has_bat_status) {
×
1068
        Telemetry::Battery new_battery;
×
1069
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1070
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1071

1072
        set_battery(new_battery);
×
1073

1074
        {
1075
            std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1076
            _battery_subscriptions.queue(
×
1077
                battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1078
        }
×
1079
    }
1080

1081
    const bool rc_ok =
×
1082
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1083

1084
    set_rc_status({rc_ok}, std::nullopt);
×
1085

1086
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1087
        set_health_gyrometer_calibration(
×
1088
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1089
    }
1090

1091
    // PX4 v1.15.3 and previous has the bug that it doesn't set 3D_ACCEL present.
1092
    // Therefore, we ignore that and look at the health flag only.
1093
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL ||
×
NEW
1094
        _system_impl->effective_autopilot() == Autopilot::Px4) {
×
1095
        set_health_accelerometer_calibration(
×
1096
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1097
    }
1098

1099
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1100
        set_health_magnetometer_calibration(
×
1101
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1102
    }
1103

1104
    const bool global_position_ok =
1105
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1106

1107
    // FIXME: There is nothing really set in PX4 for local position from what I can tell,
1108
    //        so the best we can do for now is to set it based on GPS as a fallback.
1109

1110
    const bool local_position_ok =
1111
        global_position_ok ||
×
1112
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1113
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1114

1115
    set_health_local_position(local_position_ok);
×
1116
    set_health_global_position(global_position_ok);
×
1117

1118
    set_rc_status({rc_ok}, std::nullopt);
×
1119

1120
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1121
    _rc_status_subscriptions.queue(
×
1122
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1123

1124
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1125
    set_health_armable(armable);
×
1126
    _health_all_ok_subscriptions.queue(
×
1127
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1128
}
×
1129

1130
bool TelemetryImpl::sys_status_present_enabled_health(
×
1131
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1132
{
1133
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1134
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1135
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1136
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1137
}
1138

1139
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1140
{
1141
    mavlink_battery_status_t bat_status;
1142
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1143

1144
    _has_bat_status = true;
×
1145

1146
    Telemetry::Battery new_battery;
×
1147
    new_battery.id = bat_status.id;
×
1148
    new_battery.temperature_degc = (bat_status.temperature == std::numeric_limits<int16_t>::max()) ?
×
1149
                                       static_cast<float>(NAN) :
1150
                                       bat_status.temperature * 1e-2f; // cdegC to degC
×
1151
    new_battery.voltage_v = 0.0f;
×
1152
    for (int i = 0; i < 10; ++i) {
×
1153
        if (bat_status.voltages[i] == std::numeric_limits<uint16_t>::max()) {
×
1154
            break;
×
1155
        }
1156
        new_battery.voltage_v += static_cast<float>(bat_status.voltages[i]) * 1e-3f;
×
1157
    }
1158

1159
    for (int i = 0; i < 4; ++i) {
×
1160
        if (bat_status.voltages_ext[i] == std::numeric_limits<uint16_t>::max()) {
×
1161
            // Some implementations out there set it to UINT16_MAX to signal invalid.
1162
            // That's not up to the spec but we can ignore it nevertheless to be backwards
1163
            // compatible.
1164
            break;
×
1165
        } else if (bat_status.voltages_ext[i] > 1) {
×
1166
            // A value of 1 means 0 mV.
1167
            new_battery.voltage_v += static_cast<float>(bat_status.voltages_ext[i]) * 1e-3f;
×
1168
        }
1169
    }
1170

1171
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1172
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1173
                                        static_cast<float>(NAN) :
1174
                                        bat_status.current_battery * 1e-2f; // cA to A
×
1175
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1176
                                           static_cast<float>(NAN) :
1177
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
1178
    new_battery.time_remaining_s =
×
1179
        (bat_status.time_remaining == 0 ? static_cast<float>(NAN) : bat_status.time_remaining);
×
1180

1181
    Telemetry::BatteryFunction battery_function;
1182
    switch (bat_status.battery_function) {
×
1183
        case MAV_BATTERY_FUNCTION_ALL:
×
1184
            battery_function = Telemetry::BatteryFunction::All;
×
1185
            break;
×
1186
        case MAV_BATTERY_FUNCTION_PROPULSION:
×
1187
            battery_function = Telemetry::BatteryFunction::Propulsion;
×
1188
            break;
×
1189
        case MAV_BATTERY_FUNCTION_AVIONICS:
×
1190
            battery_function = Telemetry::BatteryFunction::Avionics;
×
1191
            break;
×
1192
        case MAV_BATTERY_FUNCTION_PAYLOAD:
×
1193
            battery_function = Telemetry::BatteryFunction::Payload;
×
1194
            break;
×
1195
        case MAV_BATTERY_FUNCTION_UNKNOWN:
×
1196
        // Fallthrough
1197
        default:
1198
            battery_function = Telemetry::BatteryFunction::Unknown;
×
1199
            break;
×
1200
    }
1201
    new_battery.battery_function = battery_function;
×
1202
    set_battery(new_battery);
×
1203

1204
    {
1205
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1206
        _battery_subscriptions.queue(
×
1207
            battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1208
    }
×
1209
}
×
1210

1211
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
3✔
1212
{
1213
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
3✔
1214
        return;
×
1215
    }
1216

1217
    mavlink_heartbeat_t heartbeat;
1218
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
3✔
1219

1220
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
3✔
1221

1222
    std::lock_guard<std::mutex> lock(_subscription_mutex);
3✔
1223
    _armed_subscriptions.queue(
6✔
1224
        armed(), [this](const auto& func) { _system_impl->call_user_callback(func); });
3✔
1225

1226
    _flight_mode_subscriptions.queue(
6✔
1227
        telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode()),
3✔
1228
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1229

1230
    _health_subscriptions.queue(
3✔
1231
        health(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1232

1233
    _health_all_ok_subscriptions.queue(
6✔
1234
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
3✔
1235
}
3✔
1236

1237
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1238
{
1239
    Telemetry::StatusText new_status_text;
3✔
1240

1241
    switch (statustext.severity) {
3✔
1242
        case MAV_SEVERITY_EMERGENCY:
×
1243
            new_status_text.type = Telemetry::StatusTextType::Emergency;
×
1244
            break;
×
1245
        case MAV_SEVERITY_ALERT:
×
1246
            new_status_text.type = Telemetry::StatusTextType::Alert;
×
1247
            break;
×
1248
        case MAV_SEVERITY_CRITICAL:
×
1249
            new_status_text.type = Telemetry::StatusTextType::Critical;
×
1250
            break;
×
1251
        case MAV_SEVERITY_ERROR:
×
1252
            new_status_text.type = Telemetry::StatusTextType::Error;
×
1253
            break;
×
1254
        case MAV_SEVERITY_WARNING:
×
1255
            new_status_text.type = Telemetry::StatusTextType::Warning;
×
1256
            break;
×
1257
        case MAV_SEVERITY_NOTICE:
×
1258
            new_status_text.type = Telemetry::StatusTextType::Notice;
×
1259
            break;
×
1260
        case MAV_SEVERITY_INFO:
3✔
1261
            new_status_text.type = Telemetry::StatusTextType::Info;
3✔
1262
            break;
3✔
1263
        case MAV_SEVERITY_DEBUG:
×
1264
            new_status_text.type = Telemetry::StatusTextType::Debug;
×
1265
            break;
×
1266
        default:
×
1267
            LogWarn() << "Unknown StatusText severity";
×
1268
            new_status_text.type = Telemetry::StatusTextType::Info;
×
1269
            break;
×
1270
    }
1271

1272
    new_status_text.text = statustext.text;
3✔
1273

1274
    set_status_text(new_status_text);
3✔
1275

1276
    std::lock_guard<std::mutex> lock(_subscription_mutex);
3✔
1277
    _status_text_subscriptions.queue(
9✔
1278
        status_text(), [this](const auto& func) { _system_impl->call_user_callback(func); });
11✔
1279
}
3✔
1280

1281
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1282
{
1283
    mavlink_rc_channels_t rc_channels;
1284
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1285

1286
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1287
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1288
    }
1289

1290
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1291
    _rc_status_subscriptions.queue(
×
1292
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1293
}
×
1294

1295
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1296
{
1297
    mavlink_system_time_t system_time;
1298
    mavlink_msg_system_time_decode(&message, &system_time);
×
1299

1300
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1301

1302
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1303
    _unix_epoch_time_subscriptions.queue(
×
1304
        unix_epoch_time(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1305
}
×
1306

1307
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1308
{
1309
    mavlink_set_actuator_control_target_t target;
1310
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1311

1312
    uint32_t group = target.group_mlx;
×
1313
    std::vector<float> controls;
×
1314

1315
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1316
    // Can't use std::copy because target is packed.
1317
    for (std::size_t i = 0; i < control_size; ++i) {
×
1318
        controls.push_back(target.controls[i]);
×
1319
    }
1320

1321
    set_actuator_control_target(group, controls);
×
1322

1323
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1324
    _actuator_control_target_subscriptions.queue(
×
1325
        actuator_control_target(),
×
1326
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1327
}
×
1328

1329
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1330
{
1331
    mavlink_actuator_output_status_t status;
1332
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1333

1334
    uint32_t active = status.active;
×
1335
    std::vector<float> actuators;
×
1336

1337
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1338
    // Can't use std::copy because status is packed.
1339
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1340
        actuators.push_back(status.actuator[i]);
×
1341
    }
1342

1343
    set_actuator_output_status(active, actuators);
×
1344

1345
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1346
    _actuator_output_status_subscriptions.queue(actuator_output_status(), [this](const auto& func) {
×
1347
        _system_impl->call_user_callback(func);
×
1348
    });
×
1349
}
×
1350

1351
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1352
{
1353
    mavlink_odometry_t odometry_msg;
1354
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1355

1356
    Telemetry::Odometry odometry_struct{};
×
1357

1358
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1359
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1360
    odometry_struct.child_frame_id =
×
1361
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1362

1363
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1364
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1365
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1366

1367
    odometry_struct.q.w = odometry_msg.q[0];
×
1368
    odometry_struct.q.x = odometry_msg.q[1];
×
1369
    odometry_struct.q.y = odometry_msg.q[2];
×
1370
    odometry_struct.q.z = odometry_msg.q[3];
×
1371

1372
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1373
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1374
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1375

1376
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1377
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1378
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1379

1380
    const std::size_t len_pose_covariance =
×
1381
        sizeof(odometry_msg.pose_covariance) / sizeof(odometry_msg.pose_covariance[0]);
1382
    for (std::size_t i = 0; i < len_pose_covariance; ++i) {
×
1383
        odometry_struct.pose_covariance.covariance_matrix.push_back(
×
1384
            odometry_msg.pose_covariance[i]);
×
1385
    }
1386

1387
    const std::size_t len_velocity_covariance =
×
1388
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1389
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1390
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1391
            odometry_msg.velocity_covariance[i]);
×
1392
    }
1393

1394
    set_odometry(odometry_struct);
×
1395

1396
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1397
    _odometry_subscriptions.queue(
×
1398
        odometry(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1399
}
×
1400

1401
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1402
{
1403
    mavlink_distance_sensor_t distance_sensor_msg;
1404
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1405

1406
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1407

1408
    distance_sensor_struct.minimum_distance_m =
×
1409
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1410
    distance_sensor_struct.maximum_distance_m =
×
1411
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1412
    distance_sensor_struct.current_distance_m =
×
1413
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1414
    distance_sensor_struct.orientation = extractOrientation(distance_sensor_msg);
×
1415

1416
    set_distance_sensor(distance_sensor_struct);
×
1417

1418
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1419
    _distance_sensor_subscriptions.queue(
×
1420
        distance_sensor(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1421
}
×
1422

1423
Telemetry::EulerAngle
1424
TelemetryImpl::extractOrientation(mavlink_distance_sensor_t distance_sensor_msg)
×
1425
{
1426
    MavSensorOrientation orientation =
×
1427
        static_cast<MavSensorOrientation>(distance_sensor_msg.orientation);
×
1428

1429
    Telemetry::EulerAngle euler_angle;
×
1430
    euler_angle.roll_deg = 0;
×
1431
    euler_angle.pitch_deg = 0;
×
1432
    euler_angle.yaw_deg = 0;
×
1433

1434
    switch (orientation) {
×
1435
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_45: {
×
1436
            euler_angle.yaw_deg = 45;
×
1437
            break;
×
1438
        }
1439
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_90: {
×
1440
            euler_angle.yaw_deg = 90;
×
1441
            break;
×
1442
        }
1443
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_135: {
×
1444
            euler_angle.yaw_deg = 135;
×
1445
            break;
×
1446
        }
1447
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_180: {
×
1448
            euler_angle.yaw_deg = 180;
×
1449
            break;
×
1450
        }
1451
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_225: {
×
1452
            euler_angle.yaw_deg = 225;
×
1453
            break;
×
1454
        }
1455
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_270: {
×
1456
            euler_angle.yaw_deg = 270;
×
1457
            break;
×
1458
        }
1459
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_315: {
×
1460
            euler_angle.yaw_deg = 315;
×
1461
            break;
×
1462
        }
1463
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180: {
×
1464
            euler_angle.roll_deg = 180;
×
1465
            break;
×
1466
        }
1467
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_45: {
×
1468
            euler_angle.roll_deg = 180;
×
1469
            euler_angle.yaw_deg = 45;
×
1470
            break;
×
1471
        }
1472
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_90: {
×
1473
            euler_angle.roll_deg = 180;
×
1474
            euler_angle.yaw_deg = 90;
×
1475
            break;
×
1476
        }
1477
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_135: {
×
1478
            euler_angle.roll_deg = 180;
×
1479
            euler_angle.yaw_deg = 135;
×
1480
            break;
×
1481
        }
1482
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180: {
×
1483
            euler_angle.pitch_deg = 180;
×
1484
            break;
×
1485
        }
1486
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_225: {
×
1487
            euler_angle.roll_deg = 180;
×
1488
            euler_angle.yaw_deg = 225;
×
1489
            break;
×
1490
        }
1491
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_270: {
×
1492
            euler_angle.roll_deg = 180;
×
1493
            euler_angle.yaw_deg = 270;
×
1494
            break;
×
1495
        }
1496
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_315: {
×
1497
            euler_angle.roll_deg = 180;
×
1498
            euler_angle.yaw_deg = 315;
×
1499
            break;
×
1500
        }
1501
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90: {
×
1502
            euler_angle.roll_deg = 90;
×
1503
            break;
×
1504
        }
1505
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_45: {
×
1506
            euler_angle.roll_deg = 90;
×
1507
            euler_angle.yaw_deg = 45;
×
1508
            break;
×
1509
        }
1510
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_90: {
×
1511
            euler_angle.roll_deg = 90;
×
1512
            euler_angle.yaw_deg = 90;
×
1513
            break;
×
1514
        }
1515
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_135: {
×
1516
            euler_angle.roll_deg = 90;
×
1517
            euler_angle.yaw_deg = 135;
×
1518
            break;
×
1519
        }
1520
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270: {
×
1521
            euler_angle.roll_deg = 270;
×
1522
            break;
×
1523
        }
1524
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_45: {
×
1525
            euler_angle.roll_deg = 270;
×
1526
            euler_angle.yaw_deg = 45;
×
1527
            break;
×
1528
        }
1529
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_90: {
×
1530
            euler_angle.roll_deg = 270;
×
1531
            euler_angle.yaw_deg = 90;
×
1532
            break;
×
1533
        }
1534
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_135: {
×
1535
            euler_angle.roll_deg = 270;
×
1536
            euler_angle.yaw_deg = 135;
×
1537
            break;
×
1538
        }
1539
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_90: {
×
1540
            euler_angle.pitch_deg = 90;
×
1541
            break;
×
1542
        }
1543
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_270: {
×
1544
            euler_angle.pitch_deg = 270;
×
1545
            break;
×
1546
        }
1547
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_90: {
×
1548
            euler_angle.pitch_deg = 180;
×
1549
            euler_angle.yaw_deg = 90;
×
1550
            break;
×
1551
        }
1552
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_270: {
×
1553
            euler_angle.pitch_deg = 180;
×
1554
            euler_angle.yaw_deg = 270;
×
1555
            break;
×
1556
        }
1557
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_90: {
×
1558
            euler_angle.roll_deg = 90;
×
1559
            euler_angle.pitch_deg = 90;
×
1560
            break;
×
1561
        }
1562
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_90: {
×
1563
            euler_angle.roll_deg = 180;
×
1564
            euler_angle.pitch_deg = 90;
×
1565
            break;
×
1566
        }
1567
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_90: {
×
1568
            euler_angle.roll_deg = 270;
×
1569
            euler_angle.pitch_deg = 90;
×
1570
            break;
×
1571
        }
1572
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180: {
×
1573
            euler_angle.roll_deg = 90;
×
1574
            euler_angle.pitch_deg = 180;
×
1575
            break;
×
1576
        }
1577
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_180: {
×
1578
            euler_angle.roll_deg = 270;
×
1579
            euler_angle.pitch_deg = 180;
×
1580
            break;
×
1581
        }
1582
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_270: {
×
1583
            euler_angle.roll_deg = 90;
×
1584
            euler_angle.pitch_deg = 270;
×
1585
            break;
×
1586
        }
1587
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_270: {
×
1588
            euler_angle.roll_deg = 180;
×
1589
            euler_angle.pitch_deg = 270;
×
1590
            break;
×
1591
        }
1592
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_270: {
×
1593
            euler_angle.roll_deg = 270;
×
1594
            euler_angle.pitch_deg = 270;
×
1595
            break;
×
1596
        }
1597
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90: {
×
1598
            euler_angle.roll_deg = 90;
×
1599
            euler_angle.pitch_deg = 180;
×
1600
            euler_angle.yaw_deg = 90;
×
1601
            break;
×
1602
        }
1603
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_270: {
×
1604
            euler_angle.roll_deg = 90;
×
1605
            euler_angle.yaw_deg = 270;
×
1606
            break;
×
1607
        }
1608
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293: {
×
1609
            euler_angle.roll_deg = 90;
×
1610
            euler_angle.pitch_deg = 68;
×
1611
            euler_angle.yaw_deg = 293;
×
1612
            break;
×
1613
        }
1614
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_315: {
×
1615
            euler_angle.pitch_deg = 315;
×
1616
            break;
×
1617
        }
1618
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_315: {
×
1619
            euler_angle.roll_deg = 90;
×
1620
            euler_angle.pitch_deg = 315;
×
1621
            break;
×
1622
        }
1623
        default: {
×
1624
            euler_angle.roll_deg = 0;
×
1625
            euler_angle.pitch_deg = 0;
×
1626
            euler_angle.yaw_deg = 0;
×
1627
        }
1628
    }
1629

1630
    return euler_angle;
×
1631
}
1632

1633
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1634
{
1635
    mavlink_scaled_pressure_t scaled_pressure_msg;
1636
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1637

1638
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1639

1640
    scaled_pressure_struct.timestamp_us =
×
1641
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1642
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1643
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1644
    scaled_pressure_struct.temperature_deg =
×
1645
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1646
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1647
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1648

1649
    set_scaled_pressure(scaled_pressure_struct);
×
1650

1651
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1652
    _scaled_pressure_subscriptions.queue(
×
1653
        scaled_pressure(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1654
}
×
1655

1656
Telemetry::LandedState
1657
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1658
{
1659
    switch (extended_sys_state.landed_state) {
×
1660
        case MAV_LANDED_STATE_IN_AIR:
×
1661
            return Telemetry::LandedState::InAir;
×
1662
        case MAV_LANDED_STATE_TAKEOFF:
×
1663
            return Telemetry::LandedState::TakingOff;
×
1664
        case MAV_LANDED_STATE_LANDING:
×
1665
            return Telemetry::LandedState::Landing;
×
1666
        case MAV_LANDED_STATE_ON_GROUND:
×
1667
            return Telemetry::LandedState::OnGround;
×
1668
        default:
×
1669
            return Telemetry::LandedState::Unknown;
×
1670
    }
1671
}
1672

1673
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1674
{
1675
    switch (extended_sys_state.vtol_state) {
×
1676
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1677
            return Telemetry::VtolState::TransitionToFw;
×
1678
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1679
            return Telemetry::VtolState::TransitionToMc;
×
1680
        case MAV_VTOL_STATE_MC:
×
1681
            return Telemetry::VtolState::Mc;
×
1682
        case MAV_VTOL_STATE_FW:
×
1683
            return Telemetry::VtolState::Fw;
×
1684
        default:
×
1685
            return Telemetry::VtolState::Undefined;
×
1686
    }
1687
}
1688

1689
Telemetry::FlightMode TelemetryImpl::telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
3✔
1690
{
1691
    switch (flight_mode) {
3✔
1692
        case FlightMode::Ready:
×
1693
            return Telemetry::FlightMode::Ready;
×
1694
        case FlightMode::Takeoff:
×
1695
            return Telemetry::FlightMode::Takeoff;
×
1696
        case FlightMode::Hold:
×
1697
            return Telemetry::FlightMode::Hold;
×
1698
        case FlightMode::Mission:
×
1699
            return Telemetry::FlightMode::Mission;
×
1700
        case FlightMode::ReturnToLaunch:
×
1701
            return Telemetry::FlightMode::ReturnToLaunch;
×
1702
        case FlightMode::Land:
×
1703
            return Telemetry::FlightMode::Land;
×
1704
        case FlightMode::Offboard:
×
1705
            return Telemetry::FlightMode::Offboard;
×
1706
        case FlightMode::FollowMe:
×
1707
            return Telemetry::FlightMode::FollowMe;
×
1708
        case FlightMode::Manual:
×
1709
            return Telemetry::FlightMode::Manual;
×
1710
        case FlightMode::Posctl:
×
1711
            return Telemetry::FlightMode::Posctl;
×
1712
        case FlightMode::Altctl:
×
1713
            return Telemetry::FlightMode::Altctl;
×
1714
        case FlightMode::Rattitude:
×
1715
            return Telemetry::FlightMode::Rattitude;
×
1716
        case FlightMode::Acro:
×
1717
            return Telemetry::FlightMode::Acro;
×
1718
        case FlightMode::Stabilized:
×
1719
            return Telemetry::FlightMode::Stabilized;
×
1720
        default:
3✔
1721
            return Telemetry::FlightMode::Unknown;
3✔
1722
    }
1723
}
1724

1725
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1726
{
1727
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1728
    return _position_velocity_ned;
×
1729
}
×
1730

1731
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1732
{
1733
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1734
    _position_velocity_ned = position_velocity_ned;
×
1735
}
×
1736

1737
Telemetry::Position TelemetryImpl::position() const
4✔
1738
{
1739
    std::lock_guard<std::mutex> lock(_position_mutex);
4✔
1740
    return _position;
8✔
1741
}
4✔
1742

1743
void TelemetryImpl::set_position(Telemetry::Position position)
4✔
1744
{
1745
    std::lock_guard<std::mutex> lock(_position_mutex);
4✔
1746
    _position = position;
4✔
1747
}
4✔
1748

1749
Telemetry::Heading TelemetryImpl::heading() const
4✔
1750
{
1751
    std::lock_guard<std::mutex> lock(_heading_mutex);
4✔
1752
    return _heading;
8✔
1753
}
4✔
1754

1755
void TelemetryImpl::set_heading(Telemetry::Heading heading)
4✔
1756
{
1757
    std::lock_guard<std::mutex> lock(_heading_mutex);
4✔
1758
    _heading = heading;
4✔
1759
}
4✔
1760

1761
Telemetry::Altitude TelemetryImpl::altitude() const
×
1762
{
1763
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1764
    return _altitude;
×
1765
}
×
1766

1767
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
1768
{
1769
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1770
    _altitude = altitude;
×
1771
}
×
1772

1773
Telemetry::Wind TelemetryImpl::wind() const
×
1774
{
1775
    std::lock_guard<std::mutex> lock(_wind_mutex);
×
1776
    return _wind;
×
1777
}
×
1778

1779
void TelemetryImpl::set_wind(Telemetry::Wind wind)
×
1780
{
1781
    std::lock_guard<std::mutex> lock(_wind_mutex);
×
1782
    _wind = wind;
×
1783
}
×
1784

1785
Telemetry::Position TelemetryImpl::home() const
×
1786
{
1787
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1788
    return _home_position;
×
1789
}
×
1790

1791
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1792
{
1793
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1794
    _home_position = home_position;
×
1795
}
×
1796

1797
bool TelemetryImpl::armed() const
3✔
1798
{
1799
    return _armed;
3✔
1800
}
1801

1802
bool TelemetryImpl::in_air() const
×
1803
{
1804
    return _in_air;
×
1805
}
1806

1807
void TelemetryImpl::set_in_air(bool in_air_new)
×
1808
{
1809
    _in_air = in_air_new;
×
1810
}
×
1811

1812
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1813
{
1814
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1815
    _status_text = status_text;
3✔
1816
}
3✔
1817

1818
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1819
{
1820
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1821
    return _status_text;
3✔
1822
}
3✔
1823

1824
void TelemetryImpl::set_armed(bool armed_new)
3✔
1825
{
1826
    _armed = armed_new;
3✔
1827
}
3✔
1828

1829
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1830
{
1831
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1832
    return _attitude_quaternion;
×
1833
}
×
1834

1835
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1836
{
1837
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1838
    return _attitude_angular_velocity_body;
×
1839
}
×
1840

1841
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1842
{
1843
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1844
    return _ground_truth;
×
1845
}
×
1846

1847
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1848
{
1849
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1850
    return _fixedwing_metrics;
×
1851
}
×
1852

1853
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1854
{
1855
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1856
    return _attitude_euler;
×
1857
}
×
1858

1859
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1860
{
1861
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1862
    _attitude_quaternion = quaternion;
×
1863
}
×
1864

1865
void TelemetryImpl::set_attitude_euler(Telemetry::EulerAngle euler)
×
1866
{
1867
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1868
    _attitude_euler = euler;
×
1869
}
×
1870

1871
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1872
    Telemetry::AngularVelocityBody angular_velocity_body)
1873
{
1874
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1875
    _attitude_angular_velocity_body = angular_velocity_body;
×
1876
}
×
1877

1878
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1879
{
1880
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1881
    _ground_truth = ground_truth;
×
1882
}
×
1883

1884
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1885
{
1886
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1887
    _fixedwing_metrics = fixedwing_metrics;
×
1888
}
×
1889

1890
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
4✔
1891
{
1892
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
4✔
1893
    return _velocity_ned;
8✔
1894
}
4✔
1895

1896
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
4✔
1897
{
1898
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
4✔
1899
    _velocity_ned = velocity_ned;
4✔
1900
}
4✔
1901

1902
Telemetry::Imu TelemetryImpl::imu() const
×
1903
{
1904
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1905
    return _imu_reading_ned;
×
1906
}
×
1907

1908
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1909
{
1910
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1911
    _imu_reading_ned = imu_reading_ned;
×
1912
}
×
1913

1914
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
1915
{
1916
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1917
    return _scaled_imu;
×
1918
}
×
1919

1920
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1921
{
1922
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1923
    _scaled_imu = scaled_imu;
×
1924
}
×
1925

1926
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1927
{
1928
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1929
    return _raw_imu;
×
1930
}
×
1931

1932
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1933
{
1934
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1935
    _raw_imu = raw_imu;
×
1936
}
×
1937

1938
Telemetry::GpsInfo TelemetryImpl::gps_info() const
1✔
1939
{
1940
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
1✔
1941
    return _gps_info;
2✔
1942
}
1✔
1943

1944
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
1✔
1945
{
1946
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
1✔
1947
    _gps_info = gps_info;
1✔
1948
}
1✔
1949

1950
Telemetry::RawGps TelemetryImpl::raw_gps() const
1✔
1951
{
1952
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
1✔
1953
    return _raw_gps;
2✔
1954
}
1✔
1955

1956
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
1✔
1957
{
1958
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
1✔
1959
    _raw_gps = raw_gps;
1✔
1960
}
1✔
1961

1962
Telemetry::Battery TelemetryImpl::battery() const
×
1963
{
1964
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1965
    return _battery;
×
1966
}
×
1967

1968
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
1969
{
1970
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1971
    _battery = battery;
×
1972
}
×
1973

1974
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1975
{
1976
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
1977
}
1978

1979
Telemetry::Health TelemetryImpl::health() const
3✔
1980
{
1981
    std::lock_guard<std::mutex> lock(_health_mutex);
3✔
1982
    return _health;
6✔
1983
}
3✔
1984

1985
bool TelemetryImpl::health_all_ok() const
3✔
1986
{
1987
    std::lock_guard<std::mutex> lock(_health_mutex);
3✔
1988
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
3✔
1989
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
1990
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
1991
        return true;
×
1992
    } else {
1993
        return false;
3✔
1994
    }
1995
}
3✔
1996

1997
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
1998
{
1999
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2000
    return _rc_status;
×
2001
}
×
2002

2003
uint64_t TelemetryImpl::unix_epoch_time() const
×
2004
{
2005
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2006
    return _unix_epoch_time_us;
×
2007
}
×
2008

2009
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
2010
{
2011
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2012
    return _actuator_control_target;
×
2013
}
×
2014

2015
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
2016
{
2017
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2018
    return _actuator_output_status;
×
2019
}
×
2020

2021
Telemetry::Odometry TelemetryImpl::odometry() const
×
2022
{
2023
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2024
    return _odometry;
×
2025
}
×
2026

2027
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
2028
{
2029
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2030
    return _distance_sensor;
×
2031
}
×
2032

2033
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
2034
{
2035
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2036
    return _scaled_pressure;
×
2037
}
×
2038

2039
void TelemetryImpl::set_health_local_position(bool ok)
×
2040
{
2041
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2042
    _health.is_local_position_ok = ok;
×
2043
}
×
2044

2045
void TelemetryImpl::set_health_global_position(bool ok)
×
2046
{
2047
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2048
    _health.is_global_position_ok = ok;
×
2049
}
×
2050

2051
void TelemetryImpl::set_health_home_position(bool ok)
×
2052
{
2053
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2054
    _health.is_home_position_ok = ok;
×
2055
}
×
2056

2057
void TelemetryImpl::set_health_gyrometer_calibration(bool ok)
×
2058
{
2059
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2060
    _health.is_gyrometer_calibration_ok = ok;
×
2061
}
×
2062

2063
void TelemetryImpl::set_health_accelerometer_calibration(bool ok)
×
2064
{
2065
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2066
    _health.is_accelerometer_calibration_ok = ok;
×
2067
}
×
2068

2069
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
2070
{
2071
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2072
    _health.is_magnetometer_calibration_ok = ok;
×
2073
}
×
2074

2075
void TelemetryImpl::set_health_armable(bool ok)
×
2076
{
2077
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2078
    _health.is_armable = ok;
×
2079
}
×
2080

2081
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2082
{
2083
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2084
    return _vtol_state;
×
2085
}
×
2086

2087
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2088
{
2089
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2090
    _vtol_state = vtol_state;
×
2091
}
×
2092

2093
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2094
{
2095
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2096
    return _landed_state;
×
2097
}
×
2098

2099
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2100
{
2101
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2102
    _landed_state = landed_state;
×
2103
}
×
2104

2105
void TelemetryImpl::set_rc_status(
×
2106
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2107
{
2108
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2109

2110
    if (maybe_available) {
×
2111
        _rc_status.is_available = maybe_available.value();
×
2112
        if (maybe_available.value()) {
×
2113
            _rc_status.was_available_once = true;
×
2114
        }
2115
    }
2116

2117
    if (maybe_signal_strength_percent) {
×
2118
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2119
    }
2120
}
×
2121

2122
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2123
{
2124
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2125
    _unix_epoch_time_us = time_us;
×
2126
}
×
2127

2128
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2129
{
2130
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2131
    _actuator_control_target.group = group;
×
2132
    _actuator_control_target.controls = controls;
×
2133
}
×
2134

2135
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2136
{
2137
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2138
    _actuator_output_status.active = active;
×
2139
    _actuator_output_status.actuator = actuators;
×
2140
}
×
2141

2142
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2143
{
2144
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2145
    _odometry = odometry;
×
2146
}
×
2147

2148
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2149
{
2150
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2151
    _distance_sensor = distance_sensor;
×
2152
}
×
2153

2154
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2155
{
2156
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2157
    _scaled_pressure = scaled_pressure;
×
2158
}
×
2159

2160
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2161
    const Telemetry::PositionVelocityNedCallback& callback)
2162
{
2163
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2164
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2165
}
×
2166

2167
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2168
{
2169
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2170
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2171
}
×
2172

2173
Telemetry::PositionHandle
2174
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
3✔
2175
{
2176
    std::lock_guard<std::mutex> lock(_subscription_mutex);
3✔
2177
    return _position_subscriptions.subscribe(callback);
3✔
2178
}
3✔
2179

2180
void TelemetryImpl::unsubscribe_position(Telemetry::PositionHandle handle)
3✔
2181
{
2182
    std::lock_guard<std::mutex> lock(_subscription_mutex);
3✔
2183
    _position_subscriptions.unsubscribe(handle);
3✔
2184
}
3✔
2185

2186
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2187
{
2188
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2189
    return _home_position_subscriptions.subscribe(callback);
×
2190
}
×
2191

2192
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2193
{
2194
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2195
    _home_position_subscriptions.unsubscribe(handle);
×
2196
}
×
2197

2198
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2199
{
2200
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2201
    return _in_air_subscriptions.subscribe(callback);
×
2202
}
×
2203

2204
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2205
{
2206
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2207
    return _in_air_subscriptions.unsubscribe(handle);
×
2208
}
×
2209

2210
Telemetry::StatusTextHandle
2211
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2212
{
2213
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2214
    return _status_text_subscriptions.subscribe(callback);
2✔
2215
}
2✔
2216

2217
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2218
{
2219
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
2220
    _status_text_subscriptions.unsubscribe(handle);
1✔
2221
}
1✔
2222

2223
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2224
{
2225
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2226
    return _armed_subscriptions.subscribe(callback);
×
2227
}
×
2228

2229
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2230
{
2231
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2232
    _armed_subscriptions.unsubscribe(handle);
×
2233
}
×
2234

2235
Telemetry::AttitudeQuaternionHandle
2236
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2237
{
2238
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2239
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2240
}
×
2241

2242
void TelemetryImpl::unsubscribe_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle)
×
2243
{
2244
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2245
    _attitude_quaternion_angle_subscriptions.unsubscribe(handle);
×
2246
}
×
2247

2248
Telemetry::AttitudeEulerHandle
2249
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2250
{
2251
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2252
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2253
}
×
2254

2255
void TelemetryImpl::unsubscribe_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2256
{
2257
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2258
    _attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2259
}
×
2260

2261
Telemetry::AttitudeAngularVelocityBodyHandle
2262
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2263
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2264
{
2265
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2266
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2267
}
×
2268

2269
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2270
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2271
{
2272
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2273
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2274
}
×
2275

2276
Telemetry::FixedwingMetricsHandle
2277
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2278
{
2279
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2280
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2281
}
×
2282

2283
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2284
{
2285
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2286
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2287
}
×
2288

2289
Telemetry::GroundTruthHandle
2290
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2291
{
2292
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2293
    return _ground_truth_subscriptions.subscribe(callback);
×
2294
}
×
2295

2296
void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle)
×
2297
{
2298
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2299
    _ground_truth_subscriptions.unsubscribe(handle);
×
2300
}
×
2301

2302
Telemetry::VelocityNedHandle
2303
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2304
{
2305
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2306
    return _velocity_ned_subscriptions.subscribe(callback);
×
2307
}
×
2308

2309
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2310
{
2311
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2312
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2313
}
×
2314

2315
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2316
{
2317
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2318
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2319
}
×
2320

2321
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2322
{
2323
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2324
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2325
}
×
2326

2327
Telemetry::ScaledImuHandle
2328
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2329
{
2330
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2331
    return _scaled_imu_subscriptions.subscribe(callback);
×
2332
}
×
2333

2334
void TelemetryImpl::unsubscribe_scaled_imu(Telemetry::ScaledImuHandle handle)
×
2335
{
2336
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2337
    _scaled_imu_subscriptions.unsubscribe(handle);
×
2338
}
×
2339

2340
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2341
{
2342
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2343
    return _raw_imu_subscriptions.subscribe(callback);
×
2344
}
×
2345

2346
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2347
{
2348
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2349
    _raw_imu_subscriptions.unsubscribe(handle);
×
2350
}
×
2351

2352
Telemetry::GpsInfoHandle
2353
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2354
{
2355
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2356
    return _gps_info_subscriptions.subscribe(callback);
×
2357
}
×
2358

2359
void TelemetryImpl::unsubscribe_gps_info(Telemetry::GpsInfoHandle handle)
×
2360
{
2361
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2362
    _gps_info_subscriptions.unsubscribe(handle);
×
2363
}
×
2364

2365
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2366
{
2367
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2368
    return _raw_gps_subscriptions.subscribe(callback);
×
2369
}
×
2370

2371
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2372
{
2373
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2374
    _raw_gps_subscriptions.unsubscribe(handle);
×
2375
}
×
2376

2377
Telemetry::BatteryHandle
2378
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2379
{
2380
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2381
    return _battery_subscriptions.subscribe(callback);
×
2382
}
×
2383

2384
void TelemetryImpl::unsubscribe_battery(Telemetry::BatteryHandle handle)
×
2385
{
2386
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2387
    _battery_subscriptions.unsubscribe(handle);
×
2388
}
×
2389

2390
Telemetry::FlightModeHandle
2391
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2392
{
2393
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2394
    return _flight_mode_subscriptions.subscribe(callback);
×
2395
}
×
2396

2397
void TelemetryImpl::unsubscribe_flight_mode(Telemetry::FlightModeHandle handle)
×
2398
{
2399
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2400
    _flight_mode_subscriptions.unsubscribe(handle);
×
2401
}
×
2402

2403
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2404
{
2405
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2406
    return _health_subscriptions.subscribe(callback);
×
2407
}
×
2408

2409
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2410
{
2411
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2412
    _health_subscriptions.unsubscribe(handle);
×
2413
}
×
2414

2415
Telemetry::HealthAllOkHandle
2416
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2417
{
2418
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2419
    return _health_all_ok_subscriptions.subscribe(callback);
×
2420
}
×
2421

2422
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2423
{
2424
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2425
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2426
}
×
2427

2428
Telemetry::VtolStateHandle
2429
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2430
{
2431
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2432
    return _vtol_state_subscriptions.subscribe(callback);
×
2433
}
×
2434

2435
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2436
{
2437
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2438
    _vtol_state_subscriptions.unsubscribe(handle);
×
2439
}
×
2440

2441
Telemetry::LandedStateHandle
2442
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2443
{
2444
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2445
    return _landed_state_subscriptions.subscribe(callback);
×
2446
}
×
2447

2448
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2449
{
2450
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2451
    _landed_state_subscriptions.unsubscribe(handle);
×
2452
}
×
2453

2454
Telemetry::RcStatusHandle
2455
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2456
{
2457
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2458
    return _rc_status_subscriptions.subscribe(callback);
×
2459
}
×
2460

2461
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2462
{
2463
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2464
    _rc_status_subscriptions.unsubscribe(handle);
×
2465
}
×
2466

2467
Telemetry::UnixEpochTimeHandle
2468
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2469
{
2470
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2471
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2472
}
×
2473

2474
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2475
{
2476
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2477
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2478
}
×
2479

2480
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2481
    const Telemetry::ActuatorControlTargetCallback& callback)
2482
{
2483
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2484
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2485
}
×
2486

2487
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2488
    Telemetry::ActuatorControlTargetHandle handle)
2489
{
2490
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2491
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2492
}
×
2493

2494
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2495
    const Telemetry::ActuatorOutputStatusCallback& callback)
2496
{
2497
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2498
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2499
}
×
2500

2501
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2502
{
2503
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2504
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2505
}
×
2506

2507
Telemetry::OdometryHandle
2508
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2509
{
2510
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2511
    return _odometry_subscriptions.subscribe(callback);
×
2512
}
×
2513

2514
void TelemetryImpl::unsubscribe_odometry(Telemetry::OdometryHandle handle)
×
2515
{
2516
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2517
    _odometry_subscriptions.unsubscribe(handle);
×
2518
}
×
2519

2520
Telemetry::DistanceSensorHandle
2521
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2522
{
2523
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2524
    return _distance_sensor_subscriptions.subscribe(callback);
×
2525
}
×
2526

2527
void TelemetryImpl::unsubscribe_distance_sensor(Telemetry::DistanceSensorHandle handle)
×
2528
{
2529
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2530
    _distance_sensor_subscriptions.unsubscribe(handle);
×
2531
}
×
2532

2533
Telemetry::ScaledPressureHandle
2534
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2535
{
2536
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2537
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2538
}
×
2539

2540
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2541
{
2542
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2543
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2544
}
×
2545

2546
Telemetry::HeadingHandle
2547
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2548
{
2549
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2550
    return _heading_subscriptions.subscribe(callback);
×
2551
}
×
2552

2553
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2554
{
2555
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2556
    _heading_subscriptions.unsubscribe(handle);
×
2557
}
×
2558

2559
Telemetry::AltitudeHandle
2560
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2561
{
2562
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2563
    return _altitude_subscriptions.subscribe(callback);
×
2564
}
×
2565

2566
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2567
{
2568
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2569
    _altitude_subscriptions.unsubscribe(handle);
×
2570
}
×
2571

2572
Telemetry::WindHandle TelemetryImpl::subscribe_wind(const Telemetry::WindCallback& callback)
×
2573
{
2574
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2575
    return _wind_subscriptions.subscribe(callback);
×
2576
}
×
2577

2578
void TelemetryImpl::unsubscribe_wind(Telemetry::WindHandle handle)
×
2579
{
2580
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2581
    _wind_subscriptions.unsubscribe(handle);
×
2582
}
×
2583

2584
void TelemetryImpl::get_gps_global_origin_async(
×
2585
    const Telemetry::GetGpsGlobalOriginCallback callback)
2586
{
2587
    _system_impl->mavlink_request_message().request(
×
2588
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2589
        MAV_COMP_ID_AUTOPILOT1,
2590
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2591
            if (result == MavlinkCommandSender::Result::Success) {
×
2592
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
2593
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2594

2595
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2596
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2597
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2598
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2599
                _system_impl->call_user_callback([callback, gps_global_origin]() {
×
2600
                    callback(Telemetry::Result::Success, gps_global_origin);
2601
                });
2602

2603
            } else {
2604
                _system_impl->call_user_callback([callback, result]() {
×
2605
                    callback(telemetry_result_from_command_result(result), {});
2606
                });
2607
            }
2608
        });
×
2609
}
×
2610

2611
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2612
{
2613
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2614
    auto fut = prom.get_future();
×
2615

2616
    get_gps_global_origin_async(
×
2617
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2618
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2619
        });
×
2620
    return fut.get();
×
2621
}
×
2622

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

© 2026 Coveralls, Inc