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

mavlink / MAVSDK / 13934227568

18 Mar 2025 09:54PM UTC coverage: 44.344% (-0.08%) from 44.424%
13934227568

push

github

web-flow
Merge pull request #2523 from aminballoon/pr-add-Mavlink-Wind

Add mavlink wind

1 of 79 new or added lines in 2 files covered. (1.27%)

9 existing lines in 4 files now uncovered.

14601 of 32927 relevant lines covered (44.34%)

283.95 hits per line

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

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

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

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

71
    _system_impl->register_mavlink_message_handler(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
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(
1✔
177
        MAVLINK_MSG_ID_WIND_COV,
NEW
178
        [this](const mavlink_message_t& message) { process_wind(message); },
×
179
        this);
180

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

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

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

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

210
void TelemetryImpl::request_home_position_again()
1✔
211
{
212
    {
213
        std::lock_guard<std::mutex> lock(_health_mutex);
1✔
214
        if (_health.is_home_position_ok) {
1✔
215
            _system_impl->remove_call_every(_homepos_cookie);
×
216
            return;
×
217
        }
218

219
        _system_impl->mavlink_request_message().request(
1✔
220
            MAVLINK_MSG_ID_HOME_POSITION, MAV_COMP_ID_AUTOPILOT1, nullptr);
221
    }
1✔
222
}
223

224
Telemetry::Result TelemetryImpl::set_rate_position_velocity_ned(double rate_hz)
×
225
{
226
    return telemetry_result_from_command_result(
×
227
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_LOCAL_POSITION_NED, rate_hz));
×
228
}
229

230
Telemetry::Result TelemetryImpl::set_rate_position(double rate_hz)
×
231
{
232
    _position_rate_hz = rate_hz;
×
233
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
234

235
    return telemetry_result_from_command_result(
×
236
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
237
}
238

239
Telemetry::Result TelemetryImpl::set_rate_home(double rate_hz)
×
240
{
241
    return telemetry_result_from_command_result(
×
242
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HOME_POSITION, rate_hz));
×
243
}
244

245
Telemetry::Result TelemetryImpl::set_rate_in_air(double rate_hz)
×
246
{
247
    return set_rate_landed_state(rate_hz);
×
248
}
249

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

255
Telemetry::Result TelemetryImpl::set_rate_landed_state(double rate_hz)
×
256
{
257
    return telemetry_result_from_command_result(
×
258
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_EXTENDED_SYS_STATE, rate_hz));
×
259
}
260

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

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

273
Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz)
×
274
{
275
    _velocity_ned_rate_hz = rate_hz;
×
276
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
277

278
    return telemetry_result_from_command_result(
×
279
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
280
}
281

282
Telemetry::Result TelemetryImpl::set_rate_imu(double rate_hz)
×
283
{
284
    return telemetry_result_from_command_result(
×
285
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIGHRES_IMU, rate_hz));
×
286
}
287

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

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

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

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

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

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

324
Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz)
×
325
{
326
    UNUSED(rate_hz);
×
327
    LogWarn() << "System status is usually fixed at 1 Hz";
×
328
    return Telemetry::Result::Unsupported;
×
329
}
330

331
Telemetry::Result TelemetryImpl::set_rate_actuator_control_target(double rate_hz)
×
332
{
333
    return telemetry_result_from_command_result(
×
334
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, rate_hz));
×
335
}
336

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

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

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

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

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

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

373
void TelemetryImpl::set_rate_position_velocity_ned_async(
×
374
    double rate_hz, Telemetry::ResultCallback callback)
375
{
376
    _system_impl->set_msg_rate_async(
×
377
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
378
        rate_hz,
379
        [callback](MavlinkCommandSender::Result command_result, float) {
×
380
            command_result_callback(command_result, callback);
×
381
        });
×
382
}
×
383

384
void TelemetryImpl::set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
385
{
386
    _position_rate_hz = rate_hz;
×
387
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
388

389
    _system_impl->set_msg_rate_async(
×
390
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
391
        max_rate_hz,
392
        [callback](MavlinkCommandSender::Result command_result, float) {
×
393
            command_result_callback(command_result, callback);
×
394
        });
×
395
}
×
396

397
void TelemetryImpl::set_rate_home_async(double rate_hz, Telemetry::ResultCallback callback)
×
398
{
399
    _system_impl->set_msg_rate_async(
×
400
        MAVLINK_MSG_ID_HOME_POSITION,
401
        rate_hz,
402
        [callback](MavlinkCommandSender::Result command_result, float) {
×
403
            command_result_callback(command_result, callback);
×
404
        });
×
405
}
×
406

407
void TelemetryImpl::set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
408
{
409
    set_rate_landed_state_async(rate_hz, callback);
×
410
}
×
411

412
void TelemetryImpl::set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
413
{
414
    set_rate_landed_state_async(rate_hz, callback);
×
415
}
×
416

417
void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
418
{
419
    _system_impl->set_msg_rate_async(
×
420
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
421
        rate_hz,
422
        [callback](MavlinkCommandSender::Result command_result, float) {
×
423
            command_result_callback(command_result, callback);
×
424
        });
×
425
}
×
426

427
void TelemetryImpl::set_rate_altitude_async(double rate_hz, Telemetry::ResultCallback callback)
×
428
{
429
    _system_impl->set_msg_rate_async(
×
430
        MAVLINK_MSG_ID_ALTITUDE,
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_attitude_quaternion_async(
×
438
    double rate_hz, Telemetry::ResultCallback callback)
439
{
440
    _system_impl->set_msg_rate_async(
×
441
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
442
        rate_hz,
443
        [callback](MavlinkCommandSender::Result command_result, float) {
×
444
            command_result_callback(command_result, callback);
×
445
        });
×
446
}
×
447

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

459
void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
460
{
461
    _velocity_ned_rate_hz = rate_hz;
×
462
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
463

464
    _system_impl->set_msg_rate_async(
×
465
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
466
        max_rate_hz,
467
        [callback](MavlinkCommandSender::Result command_result, float) {
×
468
            command_result_callback(command_result, callback);
×
469
        });
×
470
}
×
471

472
void TelemetryImpl::set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
473
{
474
    _system_impl->set_msg_rate_async(
×
475
        MAVLINK_MSG_ID_HIGHRES_IMU,
476
        rate_hz,
477
        [callback](MavlinkCommandSender::Result command_result, float) {
×
478
            command_result_callback(command_result, callback);
×
479
        });
×
480
}
×
481

482
void TelemetryImpl::set_rate_scaled_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
483
{
484
    _system_impl->set_msg_rate_async(
×
485
        MAVLINK_MSG_ID_SCALED_IMU,
486
        rate_hz,
487
        [callback](MavlinkCommandSender::Result command_result, float) {
×
488
            command_result_callback(command_result, callback);
×
489
        });
×
490
}
×
491

492
void TelemetryImpl::set_rate_raw_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
493
{
494
    _system_impl->set_msg_rate_async(
×
495
        MAVLINK_MSG_ID_RAW_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_fixedwing_metrics_async(
×
503
    double rate_hz, Telemetry::ResultCallback callback)
504
{
505
    _system_impl->set_msg_rate_async(
×
506
        MAVLINK_MSG_ID_VFR_HUD,
507
        rate_hz,
508
        [callback](MavlinkCommandSender::Result command_result, float) {
×
509
            command_result_callback(command_result, callback);
×
510
        });
×
511
}
×
512

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

523
void TelemetryImpl::set_rate_gps_info_async(double rate_hz, Telemetry::ResultCallback callback)
×
524
{
525
    _system_impl->set_msg_rate_async(
×
526
        MAVLINK_MSG_ID_GPS_RAW_INT,
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_battery_async(double rate_hz, Telemetry::ResultCallback callback)
×
534
{
535
    _system_impl->set_msg_rate_async(
×
536
        MAVLINK_MSG_ID_BATTERY_STATUS,
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_rc_status_async(double rate_hz, Telemetry::ResultCallback callback)
×
544
{
545
    UNUSED(rate_hz);
×
546
    LogWarn() << "System status is usually fixed at 1 Hz";
×
547
    _system_impl->call_user_callback([callback]() { callback(Telemetry::Result::Unsupported); });
×
548
}
×
549

550
void TelemetryImpl::set_rate_unix_epoch_time_async(
×
551
    double rate_hz, Telemetry::ResultCallback callback)
552
{
553
    _system_impl->set_msg_rate_async(
×
554
        MAVLINK_MSG_ID_UTM_GLOBAL_POSITION,
555
        rate_hz,
556
        [callback](MavlinkCommandSender::Result command_result, float) {
×
557
            command_result_callback(command_result, callback);
×
558
        });
×
559
}
×
560

561
void TelemetryImpl::set_rate_actuator_control_target_async(
×
562
    double rate_hz, Telemetry::ResultCallback callback)
563
{
564
    _system_impl->set_msg_rate_async(
×
565
        MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET,
566
        rate_hz,
567
        [callback](MavlinkCommandSender::Result command_result, float) {
×
568
            command_result_callback(command_result, callback);
×
569
        });
×
570
}
×
571

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

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

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

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

615
Telemetry::Result
616
TelemetryImpl::telemetry_result_from_command_result(MavlinkCommandSender::Result command_result)
×
617
{
618
    switch (command_result) {
×
619
        case MavlinkCommandSender::Result::Success:
×
620
            return Telemetry::Result::Success;
×
621
        case MavlinkCommandSender::Result::NoSystem:
×
622
            return Telemetry::Result::NoSystem;
×
623
        case MavlinkCommandSender::Result::ConnectionError:
×
624
            return Telemetry::Result::ConnectionError;
×
625
        case MavlinkCommandSender::Result::Busy:
×
626
            return Telemetry::Result::Busy;
×
627
        case MavlinkCommandSender::Result::Denied:
×
628
            // FALLTHROUGH
629
        case MavlinkCommandSender::Result::TemporarilyRejected:
630
            return Telemetry::Result::CommandDenied;
×
631
        case MavlinkCommandSender::Result::Timeout:
×
632
            return Telemetry::Result::Timeout;
×
633
        case MavlinkCommandSender::Result::Unsupported:
×
634
            return Telemetry::Result::Unsupported;
×
635
        default:
×
636
            return Telemetry::Result::Unknown;
×
637
    }
638
}
639

640
void TelemetryImpl::command_result_callback(
×
641
    MavlinkCommandSender::Result command_result, const Telemetry::ResultCallback& callback)
642
{
643
    Telemetry::Result action_result = telemetry_result_from_command_result(command_result);
×
644

645
    callback(action_result);
×
646
}
×
647

648
void TelemetryImpl::process_position_velocity_ned(const mavlink_message_t& message)
×
649
{
650
    mavlink_local_position_ned_t local_position;
×
651
    mavlink_msg_local_position_ned_decode(&message, &local_position);
×
652

653
    Telemetry::PositionVelocityNed position_velocity;
×
654
    position_velocity.position.north_m = local_position.x;
×
655
    position_velocity.position.east_m = local_position.y;
×
656
    position_velocity.position.down_m = local_position.z;
×
657
    position_velocity.velocity.north_m_s = local_position.vx;
×
658
    position_velocity.velocity.east_m_s = local_position.vy;
×
659
    position_velocity.velocity.down_m_s = local_position.vz;
×
660

661
    set_position_velocity_ned(position_velocity);
×
662

663
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
664
    _position_velocity_ned_subscriptions.queue(position_velocity_ned(), [this](const auto& func) {
×
665
        _system_impl->call_user_callback(func);
×
666
    });
×
667

668
    set_health_local_position(true);
×
669
}
×
670

671
void TelemetryImpl::process_global_position_int(const mavlink_message_t& message)
×
672
{
673
    mavlink_global_position_int_t global_position_int;
×
674
    mavlink_msg_global_position_int_decode(&message, &global_position_int);
×
675

676
    {
677
        Telemetry::Position position;
×
678
        position.latitude_deg = global_position_int.lat * 1e-7;
×
679
        position.longitude_deg = global_position_int.lon * 1e-7;
×
680
        position.absolute_altitude_m = global_position_int.alt * 1e-3f;
×
681
        position.relative_altitude_m = global_position_int.relative_alt * 1e-3f;
×
682
        set_position(position);
×
683
    }
684

685
    {
686
        Telemetry::VelocityNed velocity;
×
687
        velocity.north_m_s = global_position_int.vx * 1e-2f;
×
688
        velocity.east_m_s = global_position_int.vy * 1e-2f;
×
689
        velocity.down_m_s = global_position_int.vz * 1e-2f;
×
690
        set_velocity_ned(velocity);
×
691
    }
692

693
    {
694
        Telemetry::Heading heading;
×
695
        heading.heading_deg = (global_position_int.hdg != std::numeric_limits<uint16_t>::max()) ?
×
696
                                  static_cast<double>(global_position_int.hdg) * 1e-2 :
×
697
                                  static_cast<double>(NAN);
698
        set_heading(heading);
×
699
    }
700

701
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
702
    _position_subscriptions.queue(
×
703
        position(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
704

705
    _velocity_ned_subscriptions.queue(
×
706
        velocity_ned(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
707

708
    _heading_subscriptions.queue(
×
709
        heading(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
710
}
×
711

712
void TelemetryImpl::process_home_position(const mavlink_message_t& message)
×
713
{
714
    mavlink_home_position_t home_position;
×
715
    mavlink_msg_home_position_decode(&message, &home_position);
×
716
    Telemetry::Position new_pos;
×
717
    new_pos.latitude_deg = home_position.latitude * 1e-7;
×
718
    new_pos.longitude_deg = home_position.longitude * 1e-7;
×
719
    new_pos.absolute_altitude_m = home_position.altitude * 1e-3f;
×
720
    new_pos.relative_altitude_m = 0.0f; // 0 by definition.
×
721

722
    set_home_position(new_pos);
×
723

724
    set_health_home_position(true);
×
725

726
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
727
    _home_position_subscriptions.queue(
×
728
        home(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
729
}
×
730

731
void TelemetryImpl::process_attitude(const mavlink_message_t& message)
×
732
{
733
    mavlink_attitude_t attitude;
×
734
    mavlink_msg_attitude_decode(&message, &attitude);
×
735

736
    Telemetry::EulerAngle euler_angle;
×
737
    euler_angle.roll_deg = to_deg_from_rad(attitude.roll);
×
738
    euler_angle.pitch_deg = to_deg_from_rad(attitude.pitch);
×
739
    euler_angle.yaw_deg = to_deg_from_rad(attitude.yaw);
×
740
    euler_angle.timestamp_us = static_cast<uint64_t>(attitude.time_boot_ms) * 1000;
×
741
    set_attitude_euler(euler_angle);
×
742

743
    Telemetry::AngularVelocityBody angular_velocity_body;
×
744
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
745
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
746
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
747
    set_attitude_angular_velocity_body(angular_velocity_body);
×
748

749
    _attitude_euler_angle_subscriptions.queue(
×
750
        attitude_euler(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
751

752
    _attitude_angular_velocity_body_subscriptions.queue(
×
753
        attitude_angular_velocity_body(),
754
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
755
}
×
756

757
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
758
{
759
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
×
760
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
761

762
    Telemetry::Quaternion quaternion;
×
763
    quaternion.w = mavlink_attitude_quaternion.q1;
×
764
    quaternion.x = mavlink_attitude_quaternion.q2;
×
765
    quaternion.y = mavlink_attitude_quaternion.q3;
×
766
    quaternion.z = mavlink_attitude_quaternion.q4;
×
767
    quaternion.timestamp_us =
×
768
        static_cast<uint64_t>(mavlink_attitude_quaternion.time_boot_ms) * 1000;
×
769

770
    Telemetry::AngularVelocityBody angular_velocity_body;
×
771
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
772
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
773
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
774

775
    set_attitude_quaternion(quaternion);
×
776

777
    set_attitude_angular_velocity_body(angular_velocity_body);
×
778

779
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
780
    _attitude_quaternion_angle_subscriptions.queue(attitude_quaternion(), [this](const auto& func) {
×
781
        _system_impl->call_user_callback(func);
×
782
    });
×
783

784
    _attitude_angular_velocity_body_subscriptions.queue(
×
785
        attitude_angular_velocity_body(),
786
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
787
}
×
788

789
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
790
{
791
    mavlink_altitude_t mavlink_altitude;
×
792
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
793

794
    Telemetry::Altitude new_altitude;
×
795
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
796
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
797
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
798
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
799
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
800
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
801

802
    set_altitude(new_altitude);
×
803

804
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
805
    _altitude_subscriptions.queue(
×
806
        altitude(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
807
}
×
808

NEW
809
void TelemetryImpl::process_wind(const mavlink_message_t& message)
×
810
{
NEW
811
    __mavlink_wind_cov_t mavlink_wind_cov;
×
NEW
812
    mavlink_msg_wind_cov_decode(&message, &mavlink_wind_cov);
×
813

NEW
814
    Telemetry::Wind new_wind;
×
NEW
815
    new_wind.wind_x_ned_m_s = mavlink_wind_cov.wind_x;
×
NEW
816
    new_wind.wind_y_ned_m_s = mavlink_wind_cov.wind_y;
×
NEW
817
    new_wind.wind_z_ned_m_s = mavlink_wind_cov.wind_z;
×
NEW
818
    new_wind.horizontal_variability_stddev_m_s = mavlink_wind_cov.var_horiz;
×
NEW
819
    new_wind.vertical_variability_stddev_m_s = mavlink_wind_cov.var_vert;
×
NEW
820
    new_wind.wind_altitude_msl_m = mavlink_wind_cov.wind_alt;
×
NEW
821
    new_wind.horizontal_wind_speed_accuracy_m_s = mavlink_wind_cov.horiz_accuracy;
×
NEW
822
    new_wind.vertical_wind_speed_accuracy_m_s = mavlink_wind_cov.vert_accuracy;
×
823

NEW
824
    set_wind(new_wind);
×
825

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

UNCOV
831
void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message)
×
832
{
833
    mavlink_highres_imu_t highres_imu;
×
834
    mavlink_msg_highres_imu_decode(&message, &highres_imu);
×
835
    Telemetry::Imu new_imu;
×
836
    new_imu.acceleration_frd.forward_m_s2 = highres_imu.xacc;
×
837
    new_imu.acceleration_frd.right_m_s2 = highres_imu.yacc;
×
838
    new_imu.acceleration_frd.down_m_s2 = highres_imu.zacc;
×
839
    new_imu.angular_velocity_frd.forward_rad_s = highres_imu.xgyro;
×
840
    new_imu.angular_velocity_frd.right_rad_s = highres_imu.ygyro;
×
841
    new_imu.angular_velocity_frd.down_rad_s = highres_imu.zgyro;
×
842
    new_imu.magnetic_field_frd.forward_gauss = highres_imu.xmag;
×
843
    new_imu.magnetic_field_frd.right_gauss = highres_imu.ymag;
×
844
    new_imu.magnetic_field_frd.down_gauss = highres_imu.zmag;
×
845
    new_imu.temperature_degc = highres_imu.temperature;
×
846
    new_imu.timestamp_us = highres_imu.time_usec;
×
847

848
    set_imu_reading_ned(new_imu);
×
849

850
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
851
    _imu_reading_ned_subscriptions.queue(
×
852
        imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
853
}
×
854

855
void TelemetryImpl::process_scaled_imu(const mavlink_message_t& message)
×
856
{
857
    mavlink_scaled_imu_t scaled_imu_reading;
×
858
    mavlink_msg_scaled_imu_decode(&message, &scaled_imu_reading);
×
859
    Telemetry::Imu new_imu;
×
860
    new_imu.acceleration_frd.forward_m_s2 = scaled_imu_reading.xacc;
×
861
    new_imu.acceleration_frd.right_m_s2 = scaled_imu_reading.yacc;
×
862
    new_imu.acceleration_frd.down_m_s2 = scaled_imu_reading.zacc;
×
863
    new_imu.angular_velocity_frd.forward_rad_s = scaled_imu_reading.xgyro;
×
864
    new_imu.angular_velocity_frd.right_rad_s = scaled_imu_reading.ygyro;
×
865
    new_imu.angular_velocity_frd.down_rad_s = scaled_imu_reading.zgyro;
×
866
    new_imu.magnetic_field_frd.forward_gauss = scaled_imu_reading.xmag;
×
867
    new_imu.magnetic_field_frd.right_gauss = scaled_imu_reading.ymag;
×
868
    new_imu.magnetic_field_frd.down_gauss = scaled_imu_reading.zmag;
×
869
    new_imu.temperature_degc = static_cast<float>(scaled_imu_reading.temperature) * 1e-2f;
×
870
    new_imu.timestamp_us = static_cast<uint64_t>(scaled_imu_reading.time_boot_ms) * 1000;
×
871

872
    set_scaled_imu(new_imu);
×
873

874
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
875
    _scaled_imu_subscriptions.queue(
×
876
        scaled_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
877
}
×
878

879
void TelemetryImpl::process_raw_imu(const mavlink_message_t& message)
×
880
{
881
    mavlink_raw_imu_t raw_imu_reading;
×
882
    mavlink_msg_raw_imu_decode(&message, &raw_imu_reading);
×
883
    Telemetry::Imu new_imu;
×
884
    new_imu.acceleration_frd.forward_m_s2 = raw_imu_reading.xacc;
×
885
    new_imu.acceleration_frd.right_m_s2 = raw_imu_reading.yacc;
×
886
    new_imu.acceleration_frd.down_m_s2 = raw_imu_reading.zacc;
×
887
    new_imu.angular_velocity_frd.forward_rad_s = raw_imu_reading.xgyro;
×
888
    new_imu.angular_velocity_frd.right_rad_s = raw_imu_reading.ygyro;
×
889
    new_imu.angular_velocity_frd.down_rad_s = raw_imu_reading.zgyro;
×
890
    new_imu.magnetic_field_frd.forward_gauss = raw_imu_reading.xmag;
×
891
    new_imu.magnetic_field_frd.right_gauss = raw_imu_reading.ymag;
×
892
    new_imu.magnetic_field_frd.down_gauss = raw_imu_reading.zmag;
×
893
    new_imu.temperature_degc = static_cast<float>(raw_imu_reading.temperature) * 1e-2f;
×
894
    new_imu.timestamp_us = raw_imu_reading.time_usec;
×
895

896
    set_raw_imu(new_imu);
×
897

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

903
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
×
904
{
905
    mavlink_gps_raw_int_t gps_raw_int;
×
906
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
×
907

908
    Telemetry::FixType fix_type;
909
    switch (gps_raw_int.fix_type) {
×
910
        case 0:
×
911
            fix_type = Telemetry::FixType::NoGps;
×
912
            break;
×
913
        case 1:
×
914
            fix_type = Telemetry::FixType::NoFix;
×
915
            break;
×
916
        case 2:
×
917
            fix_type = Telemetry::FixType::Fix2D;
×
918
            break;
×
919
        case 3:
×
920
            fix_type = Telemetry::FixType::Fix3D;
×
921
            break;
×
922
        case 4:
×
923
            fix_type = Telemetry::FixType::FixDgps;
×
924
            break;
×
925
        case 5:
×
926
            fix_type = Telemetry::FixType::RtkFloat;
×
927
            break;
×
928
        case 6:
×
929
            fix_type = Telemetry::FixType::RtkFixed;
×
930
            break;
×
931

932
        default:
×
933
            LogErr() << "Received unknown GPS fix type!";
×
934
            fix_type = Telemetry::FixType::NoGps;
×
935
            break;
×
936
    }
937

938
    Telemetry::GpsInfo new_gps_info;
×
939
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
940
    new_gps_info.fix_type = fix_type;
×
941
    set_gps_info(new_gps_info);
×
942

943
    Telemetry::RawGps raw_gps_info;
×
944
    raw_gps_info.timestamp_us = gps_raw_int.time_usec;
×
945
    raw_gps_info.latitude_deg = gps_raw_int.lat * 1e-7;
×
946
    raw_gps_info.longitude_deg = gps_raw_int.lon * 1e-7;
×
947
    raw_gps_info.absolute_altitude_m = gps_raw_int.alt * 1e-3f;
×
948
    raw_gps_info.hdop = static_cast<float>(gps_raw_int.eph) * 1e-2f;
×
949
    raw_gps_info.vdop = static_cast<float>(gps_raw_int.epv) * 1e-2f;
×
950
    raw_gps_info.velocity_m_s = static_cast<float>(gps_raw_int.vel) * 1e-2f;
×
951
    raw_gps_info.cog_deg = static_cast<float>(gps_raw_int.cog) * 1e-2f;
×
952
    raw_gps_info.altitude_ellipsoid_m = static_cast<float>(gps_raw_int.alt_ellipsoid) * 1e-3f;
×
953
    raw_gps_info.horizontal_uncertainty_m = static_cast<float>(gps_raw_int.h_acc) * 1e-3f;
×
954
    raw_gps_info.vertical_uncertainty_m = static_cast<float>(gps_raw_int.v_acc) * 1e-3f;
×
955
    raw_gps_info.velocity_uncertainty_m_s = static_cast<float>(gps_raw_int.vel_acc) * 1e-3f;
×
956
    raw_gps_info.heading_uncertainty_deg = static_cast<float>(gps_raw_int.hdg_acc) * 1e-5f;
×
957
    raw_gps_info.yaw_deg = static_cast<float>(gps_raw_int.yaw) * 1e-2f;
×
958
    set_raw_gps(raw_gps_info);
×
959

960
    {
961
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
962
        _gps_info_subscriptions.queue(
×
963
            gps_info(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
964
        _raw_gps_subscriptions.queue(
×
965
            raw_gps(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
966
    }
×
967
}
×
968

969
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
970
{
971
    mavlink_hil_state_quaternion_t hil_state_quaternion;
×
972
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
973

974
    Telemetry::GroundTruth new_ground_truth;
×
975
    new_ground_truth.latitude_deg = hil_state_quaternion.lat * 1e-7;
×
976
    new_ground_truth.longitude_deg = hil_state_quaternion.lon * 1e-7;
×
977
    new_ground_truth.absolute_altitude_m = hil_state_quaternion.alt * 1e-3f;
×
978

979
    set_ground_truth(new_ground_truth);
×
980

981
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
982
    _ground_truth_subscriptions.queue(
×
983
        ground_truth(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
984
}
×
985

986
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
987
{
988
    mavlink_extended_sys_state_t extended_sys_state;
×
989
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
990

991
    {
992
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
993
        set_landed_state(landed_state);
×
994

995
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
996
        set_vtol_state(vtol_state);
×
997
    }
998

999
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1000
    _landed_state_subscriptions.queue(
×
1001
        landed_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1002

1003
    _vtol_state_subscriptions.queue(
×
1004
        vtol_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1005

1006
    if (extended_sys_state.landed_state == MAV_LANDED_STATE_IN_AIR ||
×
1007
        extended_sys_state.landed_state == MAV_LANDED_STATE_TAKEOFF ||
×
1008
        extended_sys_state.landed_state == MAV_LANDED_STATE_LANDING) {
×
1009
        set_in_air(true);
×
1010
    } else if (extended_sys_state.landed_state == MAV_LANDED_STATE_ON_GROUND) {
×
1011
        set_in_air(false);
×
1012
    }
1013
    // If landed_state is undefined, we use what we have received last.
1014

1015
    _in_air_subscriptions.queue(
×
1016
        in_air(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1017
}
×
1018
void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)
×
1019
{
1020
    mavlink_vfr_hud_t vfr_hud;
×
1021
    mavlink_msg_vfr_hud_decode(&message, &vfr_hud);
×
1022

1023
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
1024
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
1025
    new_fixedwing_metrics.groundspeed_m_s = vfr_hud.groundspeed;
×
1026
    new_fixedwing_metrics.heading_deg = vfr_hud.heading;
×
1027
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
1028
    new_fixedwing_metrics.absolute_altitude_m = vfr_hud.alt;
×
1029
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1030

1031
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1032

1033
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1034
    _fixedwing_metrics_subscriptions.queue(
×
1035
        fixedwing_metrics(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1036
}
×
1037

1038
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1039
{
1040
    mavlink_sys_status_t sys_status;
×
1041
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1042

1043
    if (!_has_bat_status) {
×
1044
        Telemetry::Battery new_battery;
×
1045
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1046
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1047

1048
        set_battery(new_battery);
×
1049

1050
        {
1051
            std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1052
            _battery_subscriptions.queue(
×
1053
                battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1054
        }
×
1055
    }
1056

1057
    const bool rc_ok =
×
1058
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1059

1060
    set_rc_status({rc_ok}, std::nullopt);
×
1061

1062
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1063
        set_health_gyrometer_calibration(
×
1064
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1065
    }
1066

1067
    // PX4 v1.15.3 and previous has the bug that it doesn't set 3D_ACCEL present.
1068
    // Therefore, we ignore that and look at the health flag only.
1069
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL ||
×
1070
        _system_impl->autopilot() == Autopilot::Px4) {
×
1071
        set_health_accelerometer_calibration(
×
1072
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1073
    }
1074

1075
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1076
        set_health_magnetometer_calibration(
×
1077
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1078
    }
1079

1080
    const bool global_position_ok =
1081
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1082

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

1086
    const bool local_position_ok =
1087
        global_position_ok ||
×
1088
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1089
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1090

1091
    set_health_local_position(local_position_ok);
×
1092
    set_health_global_position(global_position_ok);
×
1093

1094
    set_rc_status({rc_ok}, std::nullopt);
×
1095

1096
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1097
    _rc_status_subscriptions.queue(
×
1098
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1099

1100
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1101
    set_health_armable(armable);
×
1102
    _health_all_ok_subscriptions.queue(
×
1103
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1104
}
×
1105

1106
bool TelemetryImpl::sys_status_present_enabled_health(
×
1107
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1108
{
1109
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1110
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1111
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1112
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1113
}
1114

1115
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1116
{
1117
    mavlink_battery_status_t bat_status;
×
1118
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1119

1120
    _has_bat_status = true;
×
1121

1122
    Telemetry::Battery new_battery;
×
1123
    new_battery.id = bat_status.id;
×
1124
    new_battery.temperature_degc = (bat_status.temperature == std::numeric_limits<int16_t>::max()) ?
×
1125
                                       static_cast<float>(NAN) :
1126
                                       bat_status.temperature * 1e-2f; // cdegC to degC
×
1127
    new_battery.voltage_v = 0.0f;
×
1128
    for (int i = 0; i < 10; ++i) {
×
1129
        if (bat_status.voltages[i] == std::numeric_limits<uint16_t>::max()) {
×
1130
            break;
×
1131
        }
1132
        new_battery.voltage_v += static_cast<float>(bat_status.voltages[i]) * 1e-3f;
×
1133
    }
1134

1135
    for (int i = 0; i < 4; ++i) {
×
1136
        if (bat_status.voltages_ext[i] == std::numeric_limits<uint16_t>::max()) {
×
1137
            // Some implementations out there set it to UINT16_MAX to signal invalid.
1138
            // That's not up to the spec but we can ignore it nevertheless to be backwards
1139
            // compatible.
1140
            break;
×
1141
        } else if (bat_status.voltages_ext[i] > 1) {
×
1142
            // A value of 1 means 0 mV.
1143
            new_battery.voltage_v += static_cast<float>(bat_status.voltages_ext[i]) * 1e-3f;
×
1144
        }
1145
    }
1146

1147
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1148
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1149
                                        static_cast<float>(NAN) :
1150
                                        bat_status.current_battery * 1e-2f; // cA to A
×
1151
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1152
                                           static_cast<float>(NAN) :
1153
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
1154

1155
    set_battery(new_battery);
×
1156

1157
    {
1158
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1159
        _battery_subscriptions.queue(
×
1160
            battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1161
    }
×
1162
}
×
1163

1164
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
1✔
1165
{
1166
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
1✔
1167
        return;
×
1168
    }
1169

1170
    mavlink_heartbeat_t heartbeat;
1✔
1171
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
1✔
1172

1173
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
1✔
1174

1175
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
1176
    _armed_subscriptions.queue(
2✔
1177
        armed(), [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1178

1179
    _flight_mode_subscriptions.queue(
2✔
1180
        telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode()),
1✔
1181
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1182

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

1186
    _health_all_ok_subscriptions.queue(
2✔
1187
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1188
}
1✔
1189

1190
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1191
{
1192
    Telemetry::StatusText new_status_text;
3✔
1193

1194
    switch (statustext.severity) {
3✔
1195
        case MAV_SEVERITY_EMERGENCY:
×
1196
            new_status_text.type = Telemetry::StatusTextType::Emergency;
×
1197
            break;
×
1198
        case MAV_SEVERITY_ALERT:
×
1199
            new_status_text.type = Telemetry::StatusTextType::Alert;
×
1200
            break;
×
1201
        case MAV_SEVERITY_CRITICAL:
×
1202
            new_status_text.type = Telemetry::StatusTextType::Critical;
×
1203
            break;
×
1204
        case MAV_SEVERITY_ERROR:
×
1205
            new_status_text.type = Telemetry::StatusTextType::Error;
×
1206
            break;
×
1207
        case MAV_SEVERITY_WARNING:
×
1208
            new_status_text.type = Telemetry::StatusTextType::Warning;
×
1209
            break;
×
1210
        case MAV_SEVERITY_NOTICE:
×
1211
            new_status_text.type = Telemetry::StatusTextType::Notice;
×
1212
            break;
×
1213
        case MAV_SEVERITY_INFO:
3✔
1214
            new_status_text.type = Telemetry::StatusTextType::Info;
3✔
1215
            break;
3✔
1216
        case MAV_SEVERITY_DEBUG:
×
1217
            new_status_text.type = Telemetry::StatusTextType::Debug;
×
1218
            break;
×
1219
        default:
×
1220
            LogWarn() << "Unknown StatusText severity";
×
1221
            new_status_text.type = Telemetry::StatusTextType::Info;
×
1222
            break;
×
1223
    }
1224

1225
    new_status_text.text = statustext.text;
3✔
1226

1227
    set_status_text(new_status_text);
3✔
1228

1229
    std::lock_guard<std::mutex> lock(_subscription_mutex);
6✔
1230
    _status_text_subscriptions.queue(
9✔
1231
        status_text(), [this](const auto& func) { _system_impl->call_user_callback(func); });
11✔
1232
}
3✔
1233

1234
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1235
{
1236
    mavlink_rc_channels_t rc_channels;
×
1237
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1238

1239
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1240
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1241
    }
1242

1243
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1244
    _rc_status_subscriptions.queue(
×
1245
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1246
}
×
1247

1248
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1249
{
1250
    mavlink_system_time_t system_time;
×
1251
    mavlink_msg_system_time_decode(&message, &system_time);
×
1252

1253
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1254

1255
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1256
    _unix_epoch_time_subscriptions.queue(
×
1257
        unix_epoch_time(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1258
}
×
1259

1260
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1261
{
1262
    mavlink_set_actuator_control_target_t target;
×
1263
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1264

1265
    uint32_t group = target.group_mlx;
×
1266
    std::vector<float> controls;
×
1267

1268
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1269
    // Can't use std::copy because target is packed.
1270
    for (std::size_t i = 0; i < control_size; ++i) {
×
1271
        controls.push_back(target.controls[i]);
×
1272
    }
1273

1274
    set_actuator_control_target(group, controls);
×
1275

1276
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1277
    _actuator_control_target_subscriptions.queue(
×
1278
        actuator_control_target(),
×
1279
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1280
}
×
1281

1282
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1283
{
1284
    mavlink_actuator_output_status_t status;
×
1285
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1286

1287
    uint32_t active = status.active;
×
1288
    std::vector<float> actuators;
×
1289

1290
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1291
    // Can't use std::copy because status is packed.
1292
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1293
        actuators.push_back(status.actuator[i]);
×
1294
    }
1295

1296
    set_actuator_output_status(active, actuators);
×
1297

1298
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1299
    _actuator_output_status_subscriptions.queue(actuator_output_status(), [this](const auto& func) {
×
1300
        _system_impl->call_user_callback(func);
×
1301
    });
×
1302
}
×
1303

1304
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1305
{
1306
    mavlink_odometry_t odometry_msg;
×
1307
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1308

1309
    Telemetry::Odometry odometry_struct{};
×
1310

1311
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1312
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1313
    odometry_struct.child_frame_id =
×
1314
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1315

1316
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1317
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1318
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1319

1320
    odometry_struct.q.w = odometry_msg.q[0];
×
1321
    odometry_struct.q.x = odometry_msg.q[1];
×
1322
    odometry_struct.q.y = odometry_msg.q[2];
×
1323
    odometry_struct.q.z = odometry_msg.q[3];
×
1324

1325
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1326
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1327
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1328

1329
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1330
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1331
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1332

1333
    const std::size_t len_pose_covariance =
×
1334
        sizeof(odometry_msg.pose_covariance) / sizeof(odometry_msg.pose_covariance[0]);
1335
    for (std::size_t i = 0; i < len_pose_covariance; ++i) {
×
1336
        odometry_struct.pose_covariance.covariance_matrix.push_back(
×
1337
            odometry_msg.pose_covariance[i]);
×
1338
    }
1339

1340
    const std::size_t len_velocity_covariance =
×
1341
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1342
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1343
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1344
            odometry_msg.velocity_covariance[i]);
×
1345
    }
1346

1347
    set_odometry(odometry_struct);
×
1348

1349
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1350
    _odometry_subscriptions.queue(
×
1351
        odometry(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1352
}
×
1353

1354
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1355
{
1356
    mavlink_distance_sensor_t distance_sensor_msg;
×
1357
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1358

1359
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1360

1361
    distance_sensor_struct.minimum_distance_m =
×
1362
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1363
    distance_sensor_struct.maximum_distance_m =
×
1364
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1365
    distance_sensor_struct.current_distance_m =
×
1366
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1367
    distance_sensor_struct.orientation = extractOrientation(distance_sensor_msg);
×
1368

1369
    set_distance_sensor(distance_sensor_struct);
×
1370

1371
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1372
    _distance_sensor_subscriptions.queue(
×
1373
        distance_sensor(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1374
}
×
1375

1376
Telemetry::EulerAngle
1377
TelemetryImpl::extractOrientation(mavlink_distance_sensor_t distance_sensor_msg)
×
1378
{
1379
    MavSensorOrientation orientation =
×
1380
        static_cast<MavSensorOrientation>(distance_sensor_msg.orientation);
×
1381

1382
    Telemetry::EulerAngle euler_angle;
×
1383
    euler_angle.roll_deg = 0;
×
1384
    euler_angle.pitch_deg = 0;
×
1385
    euler_angle.yaw_deg = 0;
×
1386

1387
    switch (orientation) {
×
1388
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_45: {
×
1389
            euler_angle.yaw_deg = 45;
×
1390
            break;
×
1391
        }
1392
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_90: {
×
1393
            euler_angle.yaw_deg = 90;
×
1394
            break;
×
1395
        }
1396
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_135: {
×
1397
            euler_angle.yaw_deg = 135;
×
1398
            break;
×
1399
        }
1400
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_180: {
×
1401
            euler_angle.yaw_deg = 180;
×
1402
            break;
×
1403
        }
1404
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_225: {
×
1405
            euler_angle.yaw_deg = 225;
×
1406
            break;
×
1407
        }
1408
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_270: {
×
1409
            euler_angle.yaw_deg = 270;
×
1410
            break;
×
1411
        }
1412
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_315: {
×
1413
            euler_angle.yaw_deg = 315;
×
1414
            break;
×
1415
        }
1416
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180: {
×
1417
            euler_angle.roll_deg = 180;
×
1418
            break;
×
1419
        }
1420
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_45: {
×
1421
            euler_angle.roll_deg = 180;
×
1422
            euler_angle.yaw_deg = 45;
×
1423
            break;
×
1424
        }
1425
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_90: {
×
1426
            euler_angle.roll_deg = 180;
×
1427
            euler_angle.yaw_deg = 90;
×
1428
            break;
×
1429
        }
1430
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_135: {
×
1431
            euler_angle.roll_deg = 180;
×
1432
            euler_angle.yaw_deg = 135;
×
1433
            break;
×
1434
        }
1435
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180: {
×
1436
            euler_angle.pitch_deg = 180;
×
1437
            break;
×
1438
        }
1439
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_225: {
×
1440
            euler_angle.roll_deg = 180;
×
1441
            euler_angle.yaw_deg = 225;
×
1442
            break;
×
1443
        }
1444
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_270: {
×
1445
            euler_angle.roll_deg = 180;
×
1446
            euler_angle.yaw_deg = 270;
×
1447
            break;
×
1448
        }
1449
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_315: {
×
1450
            euler_angle.roll_deg = 180;
×
1451
            euler_angle.yaw_deg = 315;
×
1452
            break;
×
1453
        }
1454
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90: {
×
1455
            euler_angle.roll_deg = 90;
×
1456
            break;
×
1457
        }
1458
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_45: {
×
1459
            euler_angle.roll_deg = 90;
×
1460
            euler_angle.yaw_deg = 45;
×
1461
            break;
×
1462
        }
1463
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_90: {
×
1464
            euler_angle.roll_deg = 90;
×
1465
            euler_angle.yaw_deg = 90;
×
1466
            break;
×
1467
        }
1468
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_135: {
×
1469
            euler_angle.roll_deg = 90;
×
1470
            euler_angle.yaw_deg = 135;
×
1471
            break;
×
1472
        }
1473
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270: {
×
1474
            euler_angle.roll_deg = 270;
×
1475
            break;
×
1476
        }
1477
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_45: {
×
1478
            euler_angle.roll_deg = 270;
×
1479
            euler_angle.yaw_deg = 45;
×
1480
            break;
×
1481
        }
1482
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_90: {
×
1483
            euler_angle.roll_deg = 270;
×
1484
            euler_angle.yaw_deg = 90;
×
1485
            break;
×
1486
        }
1487
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_135: {
×
1488
            euler_angle.roll_deg = 270;
×
1489
            euler_angle.yaw_deg = 135;
×
1490
            break;
×
1491
        }
1492
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_90: {
×
1493
            euler_angle.pitch_deg = 90;
×
1494
            break;
×
1495
        }
1496
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_270: {
×
1497
            euler_angle.pitch_deg = 270;
×
1498
            break;
×
1499
        }
1500
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_90: {
×
1501
            euler_angle.pitch_deg = 180;
×
1502
            euler_angle.yaw_deg = 90;
×
1503
            break;
×
1504
        }
1505
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_270: {
×
1506
            euler_angle.pitch_deg = 180;
×
1507
            euler_angle.yaw_deg = 270;
×
1508
            break;
×
1509
        }
1510
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_90: {
×
1511
            euler_angle.roll_deg = 90;
×
1512
            euler_angle.pitch_deg = 90;
×
1513
            break;
×
1514
        }
1515
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_90: {
×
1516
            euler_angle.roll_deg = 180;
×
1517
            euler_angle.pitch_deg = 90;
×
1518
            break;
×
1519
        }
1520
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_90: {
×
1521
            euler_angle.roll_deg = 270;
×
1522
            euler_angle.pitch_deg = 90;
×
1523
            break;
×
1524
        }
1525
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180: {
×
1526
            euler_angle.roll_deg = 90;
×
1527
            euler_angle.pitch_deg = 180;
×
1528
            break;
×
1529
        }
1530
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_180: {
×
1531
            euler_angle.roll_deg = 270;
×
1532
            euler_angle.pitch_deg = 180;
×
1533
            break;
×
1534
        }
1535
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_270: {
×
1536
            euler_angle.roll_deg = 90;
×
1537
            euler_angle.pitch_deg = 270;
×
1538
            break;
×
1539
        }
1540
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_270: {
×
1541
            euler_angle.roll_deg = 180;
×
1542
            euler_angle.pitch_deg = 270;
×
1543
            break;
×
1544
        }
1545
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_270: {
×
1546
            euler_angle.roll_deg = 270;
×
1547
            euler_angle.pitch_deg = 270;
×
1548
            break;
×
1549
        }
1550
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90: {
×
1551
            euler_angle.roll_deg = 90;
×
1552
            euler_angle.pitch_deg = 180;
×
1553
            euler_angle.yaw_deg = 90;
×
1554
            break;
×
1555
        }
1556
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_270: {
×
1557
            euler_angle.roll_deg = 90;
×
1558
            euler_angle.yaw_deg = 270;
×
1559
            break;
×
1560
        }
1561
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293: {
×
1562
            euler_angle.roll_deg = 90;
×
1563
            euler_angle.pitch_deg = 68;
×
1564
            euler_angle.yaw_deg = 293;
×
1565
            break;
×
1566
        }
1567
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_315: {
×
1568
            euler_angle.pitch_deg = 315;
×
1569
            break;
×
1570
        }
1571
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_315: {
×
1572
            euler_angle.roll_deg = 90;
×
1573
            euler_angle.pitch_deg = 315;
×
1574
            break;
×
1575
        }
1576
        default: {
×
1577
            euler_angle.roll_deg = 0;
×
1578
            euler_angle.pitch_deg = 0;
×
1579
            euler_angle.yaw_deg = 0;
×
1580
        }
1581
    }
1582

1583
    return euler_angle;
×
1584
}
1585

1586
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1587
{
1588
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1589
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1590

1591
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1592

1593
    scaled_pressure_struct.timestamp_us =
×
1594
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1595
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1596
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1597
    scaled_pressure_struct.temperature_deg =
×
1598
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1599
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1600
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1601

1602
    set_scaled_pressure(scaled_pressure_struct);
×
1603

1604
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1605
    _scaled_pressure_subscriptions.queue(
×
1606
        scaled_pressure(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1607
}
×
1608

1609
Telemetry::LandedState
1610
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1611
{
1612
    switch (extended_sys_state.landed_state) {
×
1613
        case MAV_LANDED_STATE_IN_AIR:
×
1614
            return Telemetry::LandedState::InAir;
×
1615
        case MAV_LANDED_STATE_TAKEOFF:
×
1616
            return Telemetry::LandedState::TakingOff;
×
1617
        case MAV_LANDED_STATE_LANDING:
×
1618
            return Telemetry::LandedState::Landing;
×
1619
        case MAV_LANDED_STATE_ON_GROUND:
×
1620
            return Telemetry::LandedState::OnGround;
×
1621
        default:
×
1622
            return Telemetry::LandedState::Unknown;
×
1623
    }
1624
}
1625

1626
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1627
{
1628
    switch (extended_sys_state.vtol_state) {
×
1629
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1630
            return Telemetry::VtolState::TransitionToFw;
×
1631
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1632
            return Telemetry::VtolState::TransitionToMc;
×
1633
        case MAV_VTOL_STATE_MC:
×
1634
            return Telemetry::VtolState::Mc;
×
1635
        case MAV_VTOL_STATE_FW:
×
1636
            return Telemetry::VtolState::Fw;
×
1637
        default:
×
1638
            return Telemetry::VtolState::Undefined;
×
1639
    }
1640
}
1641

1642
Telemetry::FlightMode TelemetryImpl::telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
1✔
1643
{
1644
    switch (flight_mode) {
1✔
1645
        case FlightMode::Ready:
×
1646
            return Telemetry::FlightMode::Ready;
×
1647
        case FlightMode::Takeoff:
×
1648
            return Telemetry::FlightMode::Takeoff;
×
1649
        case FlightMode::Hold:
×
1650
            return Telemetry::FlightMode::Hold;
×
1651
        case FlightMode::Mission:
×
1652
            return Telemetry::FlightMode::Mission;
×
1653
        case FlightMode::ReturnToLaunch:
×
1654
            return Telemetry::FlightMode::ReturnToLaunch;
×
1655
        case FlightMode::Land:
×
1656
            return Telemetry::FlightMode::Land;
×
1657
        case FlightMode::Offboard:
×
1658
            return Telemetry::FlightMode::Offboard;
×
1659
        case FlightMode::FollowMe:
×
1660
            return Telemetry::FlightMode::FollowMe;
×
1661
        case FlightMode::Manual:
×
1662
            return Telemetry::FlightMode::Manual;
×
1663
        case FlightMode::Posctl:
×
1664
            return Telemetry::FlightMode::Posctl;
×
1665
        case FlightMode::Altctl:
×
1666
            return Telemetry::FlightMode::Altctl;
×
1667
        case FlightMode::Rattitude:
×
1668
            return Telemetry::FlightMode::Rattitude;
×
1669
        case FlightMode::Acro:
×
1670
            return Telemetry::FlightMode::Acro;
×
1671
        case FlightMode::Stabilized:
×
1672
            return Telemetry::FlightMode::Stabilized;
×
1673
        default:
1✔
1674
            return Telemetry::FlightMode::Unknown;
1✔
1675
    }
1676
}
1677

1678
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1679
{
1680
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1681
    return _position_velocity_ned;
×
1682
}
×
1683

1684
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1685
{
1686
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1687
    _position_velocity_ned = position_velocity_ned;
×
1688
}
×
1689

1690
Telemetry::Position TelemetryImpl::position() const
×
1691
{
1692
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1693
    return _position;
×
1694
}
×
1695

1696
void TelemetryImpl::set_position(Telemetry::Position position)
×
1697
{
1698
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1699
    _position = position;
×
1700
}
×
1701

1702
Telemetry::Heading TelemetryImpl::heading() const
×
1703
{
1704
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1705
    return _heading;
×
1706
}
×
1707

1708
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
1709
{
1710
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1711
    _heading = heading;
×
1712
}
×
1713

1714
Telemetry::Altitude TelemetryImpl::altitude() const
×
1715
{
1716
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1717
    return _altitude;
×
1718
}
×
1719

1720
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
1721
{
1722
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1723
    _altitude = altitude;
×
1724
}
×
1725

NEW
1726
Telemetry::Wind TelemetryImpl::wind() const
×
1727
{
NEW
1728
    std::lock_guard<std::mutex> lock(_wind_mutex);
×
NEW
1729
    return _wind;
×
NEW
1730
}
×
1731

NEW
1732
void TelemetryImpl::set_wind(Telemetry::Wind wind)
×
1733
{
NEW
1734
    std::lock_guard<std::mutex> lock(_wind_mutex);
×
NEW
1735
    _wind = wind;
×
NEW
1736
}
×
1737

UNCOV
1738
Telemetry::Position TelemetryImpl::home() const
×
1739
{
1740
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1741
    return _home_position;
×
1742
}
×
1743

1744
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1745
{
1746
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1747
    _home_position = home_position;
×
1748
}
×
1749

1750
bool TelemetryImpl::armed() const
1✔
1751
{
1752
    return _armed;
1✔
1753
}
1754

1755
bool TelemetryImpl::in_air() const
×
1756
{
1757
    return _in_air;
×
1758
}
1759

1760
void TelemetryImpl::set_in_air(bool in_air_new)
×
1761
{
1762
    _in_air = in_air_new;
×
1763
}
×
1764

1765
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1766
{
1767
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1768
    _status_text = status_text;
3✔
1769
}
3✔
1770

1771
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1772
{
1773
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1774
    return _status_text;
3✔
1775
}
3✔
1776

1777
void TelemetryImpl::set_armed(bool armed_new)
1✔
1778
{
1779
    _armed = armed_new;
1✔
1780
}
1✔
1781

1782
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1783
{
1784
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1785
    return _attitude_quaternion;
×
1786
}
×
1787

1788
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1789
{
1790
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1791
    return _attitude_angular_velocity_body;
×
1792
}
×
1793

1794
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1795
{
1796
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1797
    return _ground_truth;
×
1798
}
×
1799

1800
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1801
{
1802
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1803
    return _fixedwing_metrics;
×
1804
}
×
1805

1806
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1807
{
1808
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1809
    return _attitude_euler;
×
1810
}
×
1811

1812
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1813
{
1814
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1815
    _attitude_quaternion = quaternion;
×
1816
}
×
1817

1818
void TelemetryImpl::set_attitude_euler(Telemetry::EulerAngle euler)
×
1819
{
1820
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1821
    _attitude_euler = euler;
×
1822
}
×
1823

1824
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1825
    Telemetry::AngularVelocityBody angular_velocity_body)
1826
{
1827
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1828
    _attitude_angular_velocity_body = angular_velocity_body;
×
1829
}
×
1830

1831
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1832
{
1833
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1834
    _ground_truth = ground_truth;
×
1835
}
×
1836

1837
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1838
{
1839
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1840
    _fixedwing_metrics = fixedwing_metrics;
×
1841
}
×
1842

1843
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1844
{
1845
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1846
    return _velocity_ned;
×
1847
}
×
1848

1849
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1850
{
1851
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1852
    _velocity_ned = velocity_ned;
×
1853
}
×
1854

1855
Telemetry::Imu TelemetryImpl::imu() const
×
1856
{
1857
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1858
    return _imu_reading_ned;
×
1859
}
×
1860

1861
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1862
{
1863
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1864
    _imu_reading_ned = imu_reading_ned;
×
1865
}
×
1866

1867
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
1868
{
1869
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1870
    return _scaled_imu;
×
1871
}
×
1872

1873
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1874
{
1875
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1876
    _scaled_imu = scaled_imu;
×
1877
}
×
1878

1879
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1880
{
1881
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1882
    return _raw_imu;
×
1883
}
×
1884

1885
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1886
{
1887
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1888
    _raw_imu = raw_imu;
×
1889
}
×
1890

1891
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
1892
{
1893
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1894
    return _gps_info;
×
1895
}
×
1896

1897
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
1898
{
1899
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1900
    _gps_info = gps_info;
×
1901
}
×
1902

1903
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
1904
{
1905
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1906
    return _raw_gps;
×
1907
}
×
1908

1909
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
1910
{
1911
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1912
    _raw_gps = raw_gps;
×
1913
}
×
1914

1915
Telemetry::Battery TelemetryImpl::battery() const
×
1916
{
1917
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1918
    return _battery;
×
1919
}
×
1920

1921
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
1922
{
1923
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1924
    _battery = battery;
×
1925
}
×
1926

1927
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1928
{
1929
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
1930
}
1931

1932
Telemetry::Health TelemetryImpl::health() const
1✔
1933
{
1934
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1935
    return _health;
2✔
1936
}
1✔
1937

1938
bool TelemetryImpl::health_all_ok() const
1✔
1939
{
1940
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1941
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
1✔
1942
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
1943
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
1944
        return true;
×
1945
    } else {
1946
        return false;
1✔
1947
    }
1948
}
1✔
1949

1950
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
1951
{
1952
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
1953
    return _rc_status;
×
1954
}
×
1955

1956
uint64_t TelemetryImpl::unix_epoch_time() const
×
1957
{
1958
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
1959
    return _unix_epoch_time_us;
×
1960
}
×
1961

1962
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
1963
{
1964
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
1965
    return _actuator_control_target;
×
1966
}
×
1967

1968
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
1969
{
1970
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
1971
    return _actuator_output_status;
×
1972
}
×
1973

1974
Telemetry::Odometry TelemetryImpl::odometry() const
×
1975
{
1976
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
1977
    return _odometry;
×
1978
}
×
1979

1980
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
1981
{
1982
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
1983
    return _distance_sensor;
×
1984
}
×
1985

1986
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
1987
{
1988
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
1989
    return _scaled_pressure;
×
1990
}
×
1991

1992
void TelemetryImpl::set_health_local_position(bool ok)
×
1993
{
1994
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1995
    _health.is_local_position_ok = ok;
×
1996
}
×
1997

1998
void TelemetryImpl::set_health_global_position(bool ok)
×
1999
{
2000
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2001
    _health.is_global_position_ok = ok;
×
2002
}
×
2003

2004
void TelemetryImpl::set_health_home_position(bool ok)
×
2005
{
2006
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2007
    _health.is_home_position_ok = ok;
×
2008
}
×
2009

2010
void TelemetryImpl::set_health_gyrometer_calibration(bool ok)
×
2011
{
2012
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2013
    _health.is_gyrometer_calibration_ok = ok;
×
2014
}
×
2015

2016
void TelemetryImpl::set_health_accelerometer_calibration(bool ok)
×
2017
{
2018
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2019
    _health.is_accelerometer_calibration_ok = ok;
×
2020
}
×
2021

2022
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
2023
{
2024
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2025
    _health.is_magnetometer_calibration_ok = ok;
×
2026
}
×
2027

2028
void TelemetryImpl::set_health_armable(bool ok)
×
2029
{
2030
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2031
    _health.is_armable = ok;
×
2032
}
×
2033

2034
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2035
{
2036
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2037
    return _vtol_state;
×
2038
}
×
2039

2040
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2041
{
2042
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2043
    _vtol_state = vtol_state;
×
2044
}
×
2045

2046
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2047
{
2048
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2049
    return _landed_state;
×
2050
}
×
2051

2052
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2053
{
2054
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2055
    _landed_state = landed_state;
×
2056
}
×
2057

2058
void TelemetryImpl::set_rc_status(
×
2059
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2060
{
2061
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2062

2063
    if (maybe_available) {
×
2064
        _rc_status.is_available = maybe_available.value();
×
2065
        if (maybe_available.value()) {
×
2066
            _rc_status.was_available_once = true;
×
2067
        }
2068
    }
2069

2070
    if (maybe_signal_strength_percent) {
×
2071
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2072
    }
2073
}
×
2074

2075
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2076
{
2077
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2078
    _unix_epoch_time_us = time_us;
×
2079
}
×
2080

2081
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2082
{
2083
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2084
    _actuator_control_target.group = group;
×
2085
    _actuator_control_target.controls = controls;
×
2086
}
×
2087

2088
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2089
{
2090
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2091
    _actuator_output_status.active = active;
×
2092
    _actuator_output_status.actuator = actuators;
×
2093
}
×
2094

2095
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2096
{
2097
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2098
    _odometry = odometry;
×
2099
}
×
2100

2101
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2102
{
2103
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2104
    _distance_sensor = distance_sensor;
×
2105
}
×
2106

2107
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2108
{
2109
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2110
    _scaled_pressure = scaled_pressure;
×
2111
}
×
2112

2113
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2114
    const Telemetry::PositionVelocityNedCallback& callback)
2115
{
2116
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2117
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2118
}
×
2119

2120
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2121
{
2122
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2123
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2124
}
×
2125

2126
Telemetry::PositionHandle
2127
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2128
{
2129
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2130
    return _position_subscriptions.subscribe(callback);
×
2131
}
×
2132

2133
void TelemetryImpl::unsubscribe_position(Telemetry::PositionHandle handle)
×
2134
{
2135
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2136
    _position_subscriptions.unsubscribe(handle);
×
2137
}
×
2138

2139
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2140
{
2141
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2142
    return _home_position_subscriptions.subscribe(callback);
×
2143
}
×
2144

2145
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2146
{
2147
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2148
    _home_position_subscriptions.unsubscribe(handle);
×
2149
}
×
2150

2151
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2152
{
2153
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2154
    return _in_air_subscriptions.subscribe(callback);
×
2155
}
×
2156

2157
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2158
{
2159
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2160
    return _in_air_subscriptions.unsubscribe(handle);
×
2161
}
×
2162

2163
Telemetry::StatusTextHandle
2164
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2165
{
2166
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2167
    return _status_text_subscriptions.subscribe(callback);
2✔
2168
}
2✔
2169

2170
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2171
{
2172
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
2173
    _status_text_subscriptions.unsubscribe(handle);
1✔
2174
}
1✔
2175

2176
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2177
{
2178
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2179
    return _armed_subscriptions.subscribe(callback);
×
2180
}
×
2181

2182
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2183
{
2184
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2185
    _armed_subscriptions.unsubscribe(handle);
×
2186
}
×
2187

2188
Telemetry::AttitudeQuaternionHandle
2189
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2190
{
2191
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2192
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2193
}
×
2194

2195
void TelemetryImpl::unsubscribe_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle)
×
2196
{
2197
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2198
    _attitude_quaternion_angle_subscriptions.unsubscribe(handle);
×
2199
}
×
2200

2201
Telemetry::AttitudeEulerHandle
2202
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2203
{
2204
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2205
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2206
}
×
2207

2208
void TelemetryImpl::unsubscribe_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2209
{
2210
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2211
    _attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2212
}
×
2213

2214
Telemetry::AttitudeAngularVelocityBodyHandle
2215
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2216
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2217
{
2218
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2219
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2220
}
×
2221

2222
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2223
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2224
{
2225
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2226
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2227
}
×
2228

2229
Telemetry::FixedwingMetricsHandle
2230
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2231
{
2232
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2233
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2234
}
×
2235

2236
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2237
{
2238
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2239
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2240
}
×
2241

2242
Telemetry::GroundTruthHandle
2243
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2244
{
2245
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2246
    return _ground_truth_subscriptions.subscribe(callback);
×
2247
}
×
2248

2249
void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle)
×
2250
{
2251
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2252
    _ground_truth_subscriptions.unsubscribe(handle);
×
2253
}
×
2254

2255
Telemetry::VelocityNedHandle
2256
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2257
{
2258
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2259
    return _velocity_ned_subscriptions.subscribe(callback);
×
2260
}
×
2261

2262
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2263
{
2264
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2265
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2266
}
×
2267

2268
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2269
{
2270
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2271
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2272
}
×
2273

2274
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2275
{
2276
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2277
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2278
}
×
2279

2280
Telemetry::ScaledImuHandle
2281
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2282
{
2283
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2284
    return _scaled_imu_subscriptions.subscribe(callback);
×
2285
}
×
2286

2287
void TelemetryImpl::unsubscribe_scaled_imu(Telemetry::ScaledImuHandle handle)
×
2288
{
2289
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2290
    _scaled_imu_subscriptions.unsubscribe(handle);
×
2291
}
×
2292

2293
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2294
{
2295
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2296
    return _raw_imu_subscriptions.subscribe(callback);
×
2297
}
×
2298

2299
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2300
{
2301
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2302
    _raw_imu_subscriptions.unsubscribe(handle);
×
2303
}
×
2304

2305
Telemetry::GpsInfoHandle
2306
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2307
{
2308
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2309
    return _gps_info_subscriptions.subscribe(callback);
×
2310
}
×
2311

2312
void TelemetryImpl::unsubscribe_gps_info(Telemetry::GpsInfoHandle handle)
×
2313
{
2314
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2315
    _gps_info_subscriptions.unsubscribe(handle);
×
2316
}
×
2317

2318
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2319
{
2320
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2321
    return _raw_gps_subscriptions.subscribe(callback);
×
2322
}
×
2323

2324
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2325
{
2326
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2327
    _raw_gps_subscriptions.unsubscribe(handle);
×
2328
}
×
2329

2330
Telemetry::BatteryHandle
2331
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2332
{
2333
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2334
    return _battery_subscriptions.subscribe(callback);
×
2335
}
×
2336

2337
void TelemetryImpl::unsubscribe_battery(Telemetry::BatteryHandle handle)
×
2338
{
2339
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2340
    _battery_subscriptions.unsubscribe(handle);
×
2341
}
×
2342

2343
Telemetry::FlightModeHandle
2344
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2345
{
2346
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2347
    return _flight_mode_subscriptions.subscribe(callback);
×
2348
}
×
2349

2350
void TelemetryImpl::unsubscribe_flight_mode(Telemetry::FlightModeHandle handle)
×
2351
{
2352
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2353
    _flight_mode_subscriptions.unsubscribe(handle);
×
2354
}
×
2355

2356
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2357
{
2358
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2359
    return _health_subscriptions.subscribe(callback);
×
2360
}
×
2361

2362
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2363
{
2364
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2365
    _health_subscriptions.unsubscribe(handle);
×
2366
}
×
2367

2368
Telemetry::HealthAllOkHandle
2369
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2370
{
2371
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2372
    return _health_all_ok_subscriptions.subscribe(callback);
×
2373
}
×
2374

2375
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2376
{
2377
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2378
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2379
}
×
2380

2381
Telemetry::VtolStateHandle
2382
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2383
{
2384
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2385
    return _vtol_state_subscriptions.subscribe(callback);
×
2386
}
×
2387

2388
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2389
{
2390
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2391
    _vtol_state_subscriptions.unsubscribe(handle);
×
2392
}
×
2393

2394
Telemetry::LandedStateHandle
2395
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2396
{
2397
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2398
    return _landed_state_subscriptions.subscribe(callback);
×
2399
}
×
2400

2401
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2402
{
2403
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2404
    _landed_state_subscriptions.unsubscribe(handle);
×
2405
}
×
2406

2407
Telemetry::RcStatusHandle
2408
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2409
{
2410
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2411
    return _rc_status_subscriptions.subscribe(callback);
×
2412
}
×
2413

2414
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2415
{
2416
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2417
    _rc_status_subscriptions.unsubscribe(handle);
×
2418
}
×
2419

2420
Telemetry::UnixEpochTimeHandle
2421
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2422
{
2423
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2424
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2425
}
×
2426

2427
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2428
{
2429
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2430
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2431
}
×
2432

2433
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2434
    const Telemetry::ActuatorControlTargetCallback& callback)
2435
{
2436
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2437
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2438
}
×
2439

2440
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2441
    Telemetry::ActuatorControlTargetHandle handle)
2442
{
2443
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2444
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2445
}
×
2446

2447
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2448
    const Telemetry::ActuatorOutputStatusCallback& callback)
2449
{
2450
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2451
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2452
}
×
2453

2454
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2455
{
2456
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2457
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2458
}
×
2459

2460
Telemetry::OdometryHandle
2461
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2462
{
2463
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2464
    return _odometry_subscriptions.subscribe(callback);
×
2465
}
×
2466

2467
void TelemetryImpl::unsubscribe_odometry(Telemetry::OdometryHandle handle)
×
2468
{
2469
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2470
    _odometry_subscriptions.unsubscribe(handle);
×
2471
}
×
2472

2473
Telemetry::DistanceSensorHandle
2474
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2475
{
2476
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2477
    return _distance_sensor_subscriptions.subscribe(callback);
×
2478
}
×
2479

2480
void TelemetryImpl::unsubscribe_distance_sensor(Telemetry::DistanceSensorHandle handle)
×
2481
{
2482
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2483
    _distance_sensor_subscriptions.unsubscribe(handle);
×
2484
}
×
2485

2486
Telemetry::ScaledPressureHandle
2487
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2488
{
2489
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2490
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2491
}
×
2492

2493
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2494
{
2495
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2496
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2497
}
×
2498

2499
Telemetry::HeadingHandle
2500
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2501
{
2502
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2503
    return _heading_subscriptions.subscribe(callback);
×
2504
}
×
2505

2506
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2507
{
2508
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2509
    _heading_subscriptions.unsubscribe(handle);
×
2510
}
×
2511

2512
Telemetry::AltitudeHandle
2513
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2514
{
2515
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2516
    return _altitude_subscriptions.subscribe(callback);
×
2517
}
×
2518

2519
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2520
{
2521
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2522
    _altitude_subscriptions.unsubscribe(handle);
×
2523
}
×
2524

NEW
2525
Telemetry::WindHandle TelemetryImpl::subscribe_wind(const Telemetry::WindCallback& callback)
×
2526
{
NEW
2527
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
NEW
2528
    return _wind_subscriptions.subscribe(callback);
×
NEW
2529
}
×
2530

NEW
2531
void TelemetryImpl::unsubscribe_wind(Telemetry::WindHandle handle)
×
2532
{
NEW
2533
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
NEW
2534
    _wind_subscriptions.unsubscribe(handle);
×
NEW
2535
}
×
2536

UNCOV
2537
void TelemetryImpl::get_gps_global_origin_async(
×
2538
    const Telemetry::GetGpsGlobalOriginCallback callback)
2539
{
2540
    _system_impl->mavlink_request_message().request(
×
2541
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2542
        MAV_COMP_ID_AUTOPILOT1,
2543
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2544
            if (result == MavlinkCommandSender::Result::Success) {
×
2545
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
×
2546
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2547

2548
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2549
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2550
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2551
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2552
                _system_impl->call_user_callback([callback, gps_global_origin]() {
×
2553
                    callback(Telemetry::Result::Success, gps_global_origin);
2554
                });
2555

2556
            } else {
2557
                _system_impl->call_user_callback([callback, result]() {
×
2558
                    callback(telemetry_result_from_command_result(result), {});
2559
                });
2560
            }
2561
        });
×
2562
}
×
2563

2564
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2565
{
2566
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2567
    auto fut = prom.get_future();
×
2568

2569
    get_gps_global_origin_async(
×
2570
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2571
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2572
        });
×
2573
    return fut.get();
×
2574
}
×
2575

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