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

mavlink / MAVSDK / 16667019915

01 Aug 2025 05:21AM UTC coverage: 46.17% (-0.001%) from 46.171%
16667019915

push

github

web-flow
Merge pull request #2633 from mavlink/pr-imu-units

telemetry: fix Imu units

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

15 existing lines in 4 files now uncovered.

16103 of 34878 relevant lines covered (46.17%)

360.67 hits per line

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

10.45
/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))
2✔
50
{
51
    _system_impl->register_plugin(this);
2✔
52
}
2✔
53

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

59
void TelemetryImpl::init()
2✔
60
{
61
    _system_impl->register_mavlink_message_handler(
2✔
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(
2✔
67
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
68
        [this](const mavlink_message_t& message) { process_global_position_int(message); },
1✔
69
        this);
70

71
    _system_impl->register_mavlink_message_handler(
2✔
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(
2✔
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(
2✔
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(
2✔
87
        MAVLINK_MSG_ID_GPS_RAW_INT,
88
        [this](const mavlink_message_t& message) { process_gps_raw_int(message); },
×
89
        this);
90

91
    _system_impl->register_mavlink_message_handler(
2✔
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(
2✔
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(
2✔
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(
2✔
107
        MAVLINK_MSG_ID_HEARTBEAT,
108
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
1✔
109
        this);
110

111
    _system_impl->register_mavlink_message_handler(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
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(
2✔
182
        [this](const MavlinkStatustextHandler::Statustext& statustext) {
3✔
183
            receive_statustext(statustext);
3✔
184
        },
3✔
185
        this);
186
}
2✔
187

188
void TelemetryImpl::deinit()
2✔
189
{
190
    _system_impl->unregister_statustext_handler(this);
2✔
191
    _system_impl->unregister_all_mavlink_message_handlers(this);
2✔
192
}
2✔
193

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

665
    callback(action_result);
×
666
}
×
667

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

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

681
    set_position_velocity_ned(position_velocity);
×
682

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

688
    set_health_local_position(true);
×
689
}
×
690

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

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

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

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

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

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

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

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

742
    set_home_position(new_pos);
×
743

744
    set_health_home_position(true);
×
745

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

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

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

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

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

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

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

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

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

795
    set_attitude_quaternion(quaternion);
×
796

797
    set_attitude_angular_velocity_body(angular_velocity_body);
×
798

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

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

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

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

822
    set_altitude(new_altitude);
×
823

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

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

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

844
    set_wind(new_wind);
×
845

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

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

868
    set_imu_reading_ned(new_imu);
×
869

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

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

895
    set_scaled_imu(new_imu);
×
896

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

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

919
    set_raw_imu(new_imu);
×
920

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

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

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

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

961
    Telemetry::GpsInfo new_gps_info;
×
962
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
963
    new_gps_info.fix_type = fix_type;
×
964
    set_gps_info(new_gps_info);
×
965

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

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

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

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

1002
    set_ground_truth(new_ground_truth);
×
1003

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

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

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

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

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

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

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

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

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

1054
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1055

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

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

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

1071
        set_battery(new_battery);
×
1072

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1143
    _has_bat_status = true;
×
1144

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

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

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

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

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

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

1216
    mavlink_heartbeat_t heartbeat;
1217
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
1✔
1218

1219
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
1✔
1220

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

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

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

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

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

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

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

1273
    set_status_text(new_status_text);
3✔
1274

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

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

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

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

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

1299
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1300

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

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

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

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

1320
    set_actuator_control_target(group, controls);
×
1321

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

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

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

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

1342
    set_actuator_output_status(active, actuators);
×
1343

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

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

1355
    Telemetry::Odometry odometry_struct{};
×
1356

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

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

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

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

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

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

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

1393
    set_odometry(odometry_struct);
×
1394

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

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

1405
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1406

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

1415
    set_distance_sensor(distance_sensor_struct);
×
1416

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

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

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

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

1629
    return euler_angle;
×
1630
}
1631

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

1637
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1638

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

1648
    set_scaled_pressure(scaled_pressure_struct);
×
1649

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

© 2025 Coveralls, Inc