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

mavlink / MAVSDK / 15245769160

26 May 2025 03:48AM UTC coverage: 44.311% (-0.09%) from 44.398%
15245769160

push

github

web-flow
Merge pull request #2571 from Luc-Meunier/tlm-health

telemetry: add set rate health

0 of 14 new or added lines in 2 files covered. (0.0%)

36 existing lines in 2 files now uncovered.

14899 of 33624 relevant lines covered (44.31%)

291.44 hits per line

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

5.03
/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,
UNCOV
108
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
×
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,
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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

665
    callback(action_result);
×
666
}
×
667

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

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

681
    set_position_velocity_ned(position_velocity);
×
682

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

688
    set_health_local_position(true);
×
689
}
×
690

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

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

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

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

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

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

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

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

742
    set_home_position(new_pos);
×
743

744
    set_health_home_position(true);
×
745

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

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

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

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

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

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

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

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

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

795
    set_attitude_quaternion(quaternion);
×
796

797
    set_attitude_angular_velocity_body(angular_velocity_body);
×
798

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

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

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

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

822
    set_altitude(new_altitude);
×
823

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

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

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

844
    set_wind(new_wind);
×
845

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

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

868
    set_imu_reading_ned(new_imu);
×
869

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

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

892
    set_scaled_imu(new_imu);
×
893

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

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

916
    set_raw_imu(new_imu);
×
917

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

923
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
×
924
{
925
    mavlink_gps_raw_int_t gps_raw_int;
×
926
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
×
927

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

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

958
    Telemetry::GpsInfo new_gps_info;
×
959
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
960
    new_gps_info.fix_type = fix_type;
×
961
    set_gps_info(new_gps_info);
×
962

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

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

989
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
990
{
991
    mavlink_hil_state_quaternion_t hil_state_quaternion;
×
992
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
993

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

999
    set_ground_truth(new_ground_truth);
×
1000

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

1006
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
1007
{
1008
    mavlink_extended_sys_state_t extended_sys_state;
×
1009
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
1010

1011
    {
1012
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
1013
        set_landed_state(landed_state);
×
1014

1015
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
1016
        set_vtol_state(vtol_state);
×
1017
    }
1018

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

1023
    _vtol_state_subscriptions.queue(
×
1024
        vtol_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1025

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

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

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

1051
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1052

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

1058
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1059
{
1060
    mavlink_sys_status_t sys_status;
×
1061
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1062

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

1068
        set_battery(new_battery);
×
1069

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

1077
    const bool rc_ok =
×
1078
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1079

1080
    set_rc_status({rc_ok}, std::nullopt);
×
1081

1082
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1083
        set_health_gyrometer_calibration(
×
1084
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1085
    }
1086

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

1095
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1096
        set_health_magnetometer_calibration(
×
1097
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1098
    }
1099

1100
    const bool global_position_ok =
1101
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1102

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

1106
    const bool local_position_ok =
1107
        global_position_ok ||
×
1108
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1109
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1110

1111
    set_health_local_position(local_position_ok);
×
1112
    set_health_global_position(global_position_ok);
×
1113

1114
    set_rc_status({rc_ok}, std::nullopt);
×
1115

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

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

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

1135
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1136
{
1137
    mavlink_battery_status_t bat_status;
×
1138
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1139

1140
    _has_bat_status = true;
×
1141

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

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

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

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

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

UNCOV
1207
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
×
1208
{
UNCOV
1209
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
×
1210
        return;
×
1211
    }
1212

UNCOV
1213
    mavlink_heartbeat_t heartbeat;
×
UNCOV
1214
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
×
1215

UNCOV
1216
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
×
1217

UNCOV
1218
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
UNCOV
1219
    _armed_subscriptions.queue(
×
UNCOV
1220
        armed(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1221

UNCOV
1222
    _flight_mode_subscriptions.queue(
×
UNCOV
1223
        telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode()),
×
1224
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1225

UNCOV
1226
    _health_subscriptions.queue(
×
1227
        health(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1228

UNCOV
1229
    _health_all_ok_subscriptions.queue(
×
UNCOV
1230
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
UNCOV
1231
}
×
1232

1233
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1234
{
1235
    Telemetry::StatusText new_status_text;
3✔
1236

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

1268
    new_status_text.text = statustext.text;
3✔
1269

1270
    set_status_text(new_status_text);
3✔
1271

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

1277
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1278
{
1279
    mavlink_rc_channels_t rc_channels;
×
1280
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1281

1282
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1283
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1284
    }
1285

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

1291
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1292
{
1293
    mavlink_system_time_t system_time;
×
1294
    mavlink_msg_system_time_decode(&message, &system_time);
×
1295

1296
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1297

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

1303
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1304
{
1305
    mavlink_set_actuator_control_target_t target;
×
1306
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1307

1308
    uint32_t group = target.group_mlx;
×
1309
    std::vector<float> controls;
×
1310

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

1317
    set_actuator_control_target(group, controls);
×
1318

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

1325
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1326
{
1327
    mavlink_actuator_output_status_t status;
×
1328
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1329

1330
    uint32_t active = status.active;
×
1331
    std::vector<float> actuators;
×
1332

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

1339
    set_actuator_output_status(active, actuators);
×
1340

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

1347
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1348
{
1349
    mavlink_odometry_t odometry_msg;
×
1350
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1351

1352
    Telemetry::Odometry odometry_struct{};
×
1353

1354
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1355
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1356
    odometry_struct.child_frame_id =
×
1357
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1358

1359
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1360
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1361
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1362

1363
    odometry_struct.q.w = odometry_msg.q[0];
×
1364
    odometry_struct.q.x = odometry_msg.q[1];
×
1365
    odometry_struct.q.y = odometry_msg.q[2];
×
1366
    odometry_struct.q.z = odometry_msg.q[3];
×
1367

1368
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1369
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1370
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1371

1372
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1373
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1374
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1375

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

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

1390
    set_odometry(odometry_struct);
×
1391

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

1397
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1398
{
1399
    mavlink_distance_sensor_t distance_sensor_msg;
×
1400
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1401

1402
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1403

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

1412
    set_distance_sensor(distance_sensor_struct);
×
1413

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

1419
Telemetry::EulerAngle
1420
TelemetryImpl::extractOrientation(mavlink_distance_sensor_t distance_sensor_msg)
×
1421
{
1422
    MavSensorOrientation orientation =
×
1423
        static_cast<MavSensorOrientation>(distance_sensor_msg.orientation);
×
1424

1425
    Telemetry::EulerAngle euler_angle;
×
1426
    euler_angle.roll_deg = 0;
×
1427
    euler_angle.pitch_deg = 0;
×
1428
    euler_angle.yaw_deg = 0;
×
1429

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

1626
    return euler_angle;
×
1627
}
1628

1629
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1630
{
1631
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1632
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1633

1634
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1635

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

1645
    set_scaled_pressure(scaled_pressure_struct);
×
1646

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

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

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

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

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

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

1733
Telemetry::Position TelemetryImpl::position() const
×
1734
{
1735
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1736
    return _position;
×
1737
}
×
1738

1739
void TelemetryImpl::set_position(Telemetry::Position position)
×
1740
{
1741
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1742
    _position = position;
×
1743
}
×
1744

1745
Telemetry::Heading TelemetryImpl::heading() const
×
1746
{
1747
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1748
    return _heading;
×
1749
}
×
1750

1751
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
1752
{
1753
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1754
    _heading = heading;
×
1755
}
×
1756

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

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

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

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

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

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

UNCOV
1793
bool TelemetryImpl::armed() const
×
1794
{
UNCOV
1795
    return _armed;
×
1796
}
1797

1798
bool TelemetryImpl::in_air() const
×
1799
{
1800
    return _in_air;
×
1801
}
1802

1803
void TelemetryImpl::set_in_air(bool in_air_new)
×
1804
{
1805
    _in_air = in_air_new;
×
1806
}
×
1807

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

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

UNCOV
1820
void TelemetryImpl::set_armed(bool armed_new)
×
1821
{
UNCOV
1822
    _armed = armed_new;
×
UNCOV
1823
}
×
1824

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

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

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

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

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

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

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

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

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

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

1886
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1887
{
1888
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1889
    return _velocity_ned;
×
1890
}
×
1891

1892
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1893
{
1894
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1895
    _velocity_ned = velocity_ned;
×
1896
}
×
1897

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

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

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

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

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

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

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

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

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

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

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

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

1970
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1971
{
1972
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
1973
}
1974

UNCOV
1975
Telemetry::Health TelemetryImpl::health() const
×
1976
{
UNCOV
1977
    std::lock_guard<std::mutex> lock(_health_mutex);
×
UNCOV
1978
    return _health;
×
UNCOV
1979
}
×
1980

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

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

1999
uint64_t TelemetryImpl::unix_epoch_time() const
×
2000
{
2001
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2002
    return _unix_epoch_time_us;
×
2003
}
×
2004

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

2106
    if (maybe_available) {
×
2107
        _rc_status.is_available = maybe_available.value();
×
2108
        if (maybe_available.value()) {
×
2109
            _rc_status.was_available_once = true;
×
2110
        }
2111
    }
2112

2113
    if (maybe_signal_strength_percent) {
×
2114
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2115
    }
2116
}
×
2117

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

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

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

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

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

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

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

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

2169
Telemetry::PositionHandle
2170
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2171
{
2172
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2173
    return _position_subscriptions.subscribe(callback);
×
2174
}
×
2175

2176
void TelemetryImpl::unsubscribe_position(Telemetry::PositionHandle handle)
×
2177
{
2178
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2179
    _position_subscriptions.unsubscribe(handle);
×
2180
}
×
2181

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

2599
            } else {
2600
                _system_impl->call_user_callback([callback, result]() {
×
2601
                    callback(telemetry_result_from_command_result(result), {});
2602
                });
2603
            }
2604
        });
×
2605
}
×
2606

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

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

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