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

mavlink / MAVSDK / 13874818114

15 Mar 2025 04:52PM UTC coverage: 44.372% (-0.05%) from 44.423%
13874818114

Pull #2524

github

web-flow
Merge 45ba9d95a into effa4a8ff
Pull Request #2524: PR Update Battery Remaining Time and Battery Function

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

3 existing lines in 2 files now uncovered.

14594 of 32890 relevant lines covered (44.37%)

282.55 hits per line

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

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

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

13
namespace mavsdk {
14

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

175
    _system_impl->register_statustext_handler(
1✔
176
        [this](const MavlinkStatustextHandler::Statustext& statustext) {
3✔
177
            receive_statustext(statustext);
3✔
178
        },
3✔
179
        this);
180
}
1✔
181

182
void TelemetryImpl::deinit()
1✔
183
{
184
    _system_impl->unregister_statustext_handler(this);
1✔
185
    _system_impl->unregister_all_mavlink_message_handlers(this);
1✔
186
}
1✔
187

188
void TelemetryImpl::enable()
1✔
189
{
190
    // We're going to retry until we have the Home Position.
191
    _homepos_cookie =
1✔
192
        _system_impl->add_call_every([this]() { request_home_position_again(); }, 2.0f);
3✔
193
}
1✔
194

195
void TelemetryImpl::disable()
1✔
196
{
197
    _system_impl->remove_call_every(_homepos_cookie);
1✔
198
    {
199
        std::lock_guard<std::mutex> lock(_health_mutex);
1✔
200
        _health.is_home_position_ok = false;
1✔
201
    }
1✔
202
}
1✔
203

204
void TelemetryImpl::request_home_position_again()
1✔
205
{
206
    {
207
        std::lock_guard<std::mutex> lock(_health_mutex);
1✔
208
        if (_health.is_home_position_ok) {
1✔
209
            _system_impl->remove_call_every(_homepos_cookie);
×
210
            return;
×
211
        }
212

213
        _system_impl->mavlink_request_message().request(
1✔
214
            MAVLINK_MSG_ID_HOME_POSITION, MAV_COMP_ID_AUTOPILOT1, nullptr);
215
    }
1✔
216
}
217

218
Telemetry::Result TelemetryImpl::set_rate_position_velocity_ned(double rate_hz)
×
219
{
220
    return telemetry_result_from_command_result(
×
221
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_LOCAL_POSITION_NED, rate_hz));
×
222
}
223

224
Telemetry::Result TelemetryImpl::set_rate_position(double rate_hz)
×
225
{
226
    _position_rate_hz = rate_hz;
×
227
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
228

229
    return telemetry_result_from_command_result(
×
230
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
231
}
232

233
Telemetry::Result TelemetryImpl::set_rate_home(double rate_hz)
×
234
{
235
    return telemetry_result_from_command_result(
×
236
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HOME_POSITION, rate_hz));
×
237
}
238

239
Telemetry::Result TelemetryImpl::set_rate_in_air(double rate_hz)
×
240
{
241
    return set_rate_landed_state(rate_hz);
×
242
}
243

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

249
Telemetry::Result TelemetryImpl::set_rate_landed_state(double rate_hz)
×
250
{
251
    return telemetry_result_from_command_result(
×
252
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_EXTENDED_SYS_STATE, rate_hz));
×
253
}
254

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

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

267
Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz)
×
268
{
269
    _velocity_ned_rate_hz = rate_hz;
×
270
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
271

272
    return telemetry_result_from_command_result(
×
273
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
274
}
275

276
Telemetry::Result TelemetryImpl::set_rate_imu(double rate_hz)
×
277
{
278
    return telemetry_result_from_command_result(
×
279
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIGHRES_IMU, rate_hz));
×
280
}
281

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

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

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

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

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

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

318
Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz)
×
319
{
320
    UNUSED(rate_hz);
×
321
    LogWarn() << "System status is usually fixed at 1 Hz";
×
322
    return Telemetry::Result::Unsupported;
×
323
}
324

325
Telemetry::Result TelemetryImpl::set_rate_actuator_control_target(double rate_hz)
×
326
{
327
    return telemetry_result_from_command_result(
×
328
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, rate_hz));
×
329
}
330

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

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

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

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

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

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

367
void TelemetryImpl::set_rate_position_velocity_ned_async(
×
368
    double rate_hz, Telemetry::ResultCallback callback)
369
{
370
    _system_impl->set_msg_rate_async(
×
371
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
372
        rate_hz,
373
        [callback](MavlinkCommandSender::Result command_result, float) {
×
374
            command_result_callback(command_result, callback);
×
375
        });
×
376
}
×
377

378
void TelemetryImpl::set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
379
{
380
    _position_rate_hz = rate_hz;
×
381
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
382

383
    _system_impl->set_msg_rate_async(
×
384
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
385
        max_rate_hz,
386
        [callback](MavlinkCommandSender::Result command_result, float) {
×
387
            command_result_callback(command_result, callback);
×
388
        });
×
389
}
×
390

391
void TelemetryImpl::set_rate_home_async(double rate_hz, Telemetry::ResultCallback callback)
×
392
{
393
    _system_impl->set_msg_rate_async(
×
394
        MAVLINK_MSG_ID_HOME_POSITION,
395
        rate_hz,
396
        [callback](MavlinkCommandSender::Result command_result, float) {
×
397
            command_result_callback(command_result, callback);
×
398
        });
×
399
}
×
400

401
void TelemetryImpl::set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
402
{
403
    set_rate_landed_state_async(rate_hz, callback);
×
404
}
×
405

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

411
void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
412
{
413
    _system_impl->set_msg_rate_async(
×
414
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
415
        rate_hz,
416
        [callback](MavlinkCommandSender::Result command_result, float) {
×
417
            command_result_callback(command_result, callback);
×
418
        });
×
419
}
×
420

421
void TelemetryImpl::set_rate_altitude_async(double rate_hz, Telemetry::ResultCallback callback)
×
422
{
423
    _system_impl->set_msg_rate_async(
×
424
        MAVLINK_MSG_ID_ALTITUDE,
425
        rate_hz,
426
        [callback](MavlinkCommandSender::Result command_result, float) {
×
427
            command_result_callback(command_result, callback);
×
428
        });
×
429
}
×
430

431
void TelemetryImpl::set_rate_attitude_quaternion_async(
×
432
    double rate_hz, Telemetry::ResultCallback callback)
433
{
434
    _system_impl->set_msg_rate_async(
×
435
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
436
        rate_hz,
437
        [callback](MavlinkCommandSender::Result command_result, float) {
×
438
            command_result_callback(command_result, callback);
×
439
        });
×
440
}
×
441

442
void TelemetryImpl::set_rate_attitude_euler_async(
×
443
    double rate_hz, Telemetry::ResultCallback callback)
444
{
445
    _system_impl->set_msg_rate_async(
×
446
        MAVLINK_MSG_ID_ATTITUDE,
447
        rate_hz,
448
        [callback](MavlinkCommandSender::Result command_result, float) {
×
449
            command_result_callback(command_result, callback);
×
450
        });
×
451
}
×
452

453
void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
454
{
455
    _velocity_ned_rate_hz = rate_hz;
×
456
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
457

458
    _system_impl->set_msg_rate_async(
×
459
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
460
        max_rate_hz,
461
        [callback](MavlinkCommandSender::Result command_result, float) {
×
462
            command_result_callback(command_result, callback);
×
463
        });
×
464
}
×
465

466
void TelemetryImpl::set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
467
{
468
    _system_impl->set_msg_rate_async(
×
469
        MAVLINK_MSG_ID_HIGHRES_IMU,
470
        rate_hz,
471
        [callback](MavlinkCommandSender::Result command_result, float) {
×
472
            command_result_callback(command_result, callback);
×
473
        });
×
474
}
×
475

476
void TelemetryImpl::set_rate_scaled_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
477
{
478
    _system_impl->set_msg_rate_async(
×
479
        MAVLINK_MSG_ID_SCALED_IMU,
480
        rate_hz,
481
        [callback](MavlinkCommandSender::Result command_result, float) {
×
482
            command_result_callback(command_result, callback);
×
483
        });
×
484
}
×
485

486
void TelemetryImpl::set_rate_raw_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
487
{
488
    _system_impl->set_msg_rate_async(
×
489
        MAVLINK_MSG_ID_RAW_IMU,
490
        rate_hz,
491
        [callback](MavlinkCommandSender::Result command_result, float) {
×
492
            command_result_callback(command_result, callback);
×
493
        });
×
494
}
×
495

496
void TelemetryImpl::set_rate_fixedwing_metrics_async(
×
497
    double rate_hz, Telemetry::ResultCallback callback)
498
{
499
    _system_impl->set_msg_rate_async(
×
500
        MAVLINK_MSG_ID_VFR_HUD,
501
        rate_hz,
502
        [callback](MavlinkCommandSender::Result command_result, float) {
×
503
            command_result_callback(command_result, callback);
×
504
        });
×
505
}
×
506

507
void TelemetryImpl::set_rate_ground_truth_async(double rate_hz, Telemetry::ResultCallback callback)
×
508
{
509
    _system_impl->set_msg_rate_async(
×
510
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
511
        rate_hz,
512
        [callback](MavlinkCommandSender::Result command_result, float) {
×
513
            command_result_callback(command_result, callback);
×
514
        });
×
515
}
×
516

517
void TelemetryImpl::set_rate_gps_info_async(double rate_hz, Telemetry::ResultCallback callback)
×
518
{
519
    _system_impl->set_msg_rate_async(
×
520
        MAVLINK_MSG_ID_GPS_RAW_INT,
521
        rate_hz,
522
        [callback](MavlinkCommandSender::Result command_result, float) {
×
523
            command_result_callback(command_result, callback);
×
524
        });
×
525
}
×
526

527
void TelemetryImpl::set_rate_battery_async(double rate_hz, Telemetry::ResultCallback callback)
×
528
{
529
    _system_impl->set_msg_rate_async(
×
530
        MAVLINK_MSG_ID_BATTERY_STATUS,
531
        rate_hz,
532
        [callback](MavlinkCommandSender::Result command_result, float) {
×
533
            command_result_callback(command_result, callback);
×
534
        });
×
535
}
×
536

537
void TelemetryImpl::set_rate_rc_status_async(double rate_hz, Telemetry::ResultCallback callback)
×
538
{
539
    UNUSED(rate_hz);
×
540
    LogWarn() << "System status is usually fixed at 1 Hz";
×
541
    _system_impl->call_user_callback([callback]() { callback(Telemetry::Result::Unsupported); });
×
542
}
×
543

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

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

566
void TelemetryImpl::set_rate_actuator_output_status_async(
×
567
    double rate_hz, Telemetry::ResultCallback callback)
568
{
569
    _system_impl->set_msg_rate_async(
×
570
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
571
        rate_hz,
572
        [callback](MavlinkCommandSender::Result command_result, float) {
×
573
            command_result_callback(command_result, callback);
×
574
        });
×
575
}
×
576

577
void TelemetryImpl::set_rate_odometry_async(double rate_hz, Telemetry::ResultCallback callback)
×
578
{
579
    _system_impl->set_msg_rate_async(
×
580
        MAVLINK_MSG_ID_ODOMETRY,
581
        rate_hz,
582
        [callback](MavlinkCommandSender::Result command_result, float) {
×
583
            command_result_callback(command_result, callback);
×
584
        });
×
585
}
×
586

587
void TelemetryImpl::set_rate_distance_sensor_async(
×
588
    double rate_hz, Telemetry::ResultCallback callback)
589
{
590
    _system_impl->set_msg_rate_async(
×
591
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
592
        rate_hz,
593
        [callback](MavlinkCommandSender::Result command_result, float) {
×
594
            command_result_callback(command_result, callback);
×
595
        });
×
596
}
×
597

598
void TelemetryImpl::set_rate_scaled_pressure_async(
×
599
    double rate_hz, Telemetry::ResultCallback callback)
600
{
601
    _system_impl->set_msg_rate_async(
×
602
        MAVLINK_MSG_ID_SCALED_PRESSURE,
603
        rate_hz,
604
        [callback](MavlinkCommandSender::Result command_result, float) {
×
605
            command_result_callback(command_result, callback);
×
606
        });
×
607
}
×
608

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

634
void TelemetryImpl::command_result_callback(
×
635
    MavlinkCommandSender::Result command_result, const Telemetry::ResultCallback& callback)
636
{
637
    Telemetry::Result action_result = telemetry_result_from_command_result(command_result);
×
638

639
    callback(action_result);
×
640
}
×
641

642
void TelemetryImpl::process_position_velocity_ned(const mavlink_message_t& message)
×
643
{
644
    mavlink_local_position_ned_t local_position;
×
645
    mavlink_msg_local_position_ned_decode(&message, &local_position);
×
646

647
    Telemetry::PositionVelocityNed position_velocity;
×
648
    position_velocity.position.north_m = local_position.x;
×
649
    position_velocity.position.east_m = local_position.y;
×
650
    position_velocity.position.down_m = local_position.z;
×
651
    position_velocity.velocity.north_m_s = local_position.vx;
×
652
    position_velocity.velocity.east_m_s = local_position.vy;
×
653
    position_velocity.velocity.down_m_s = local_position.vz;
×
654

655
    set_position_velocity_ned(position_velocity);
×
656

657
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
658
    _position_velocity_ned_subscriptions.queue(position_velocity_ned(), [this](const auto& func) {
×
659
        _system_impl->call_user_callback(func);
×
660
    });
×
661

662
    set_health_local_position(true);
×
663
}
×
664

665
void TelemetryImpl::process_global_position_int(const mavlink_message_t& message)
×
666
{
667
    mavlink_global_position_int_t global_position_int;
×
668
    mavlink_msg_global_position_int_decode(&message, &global_position_int);
×
669

670
    {
671
        Telemetry::Position position;
×
672
        position.latitude_deg = global_position_int.lat * 1e-7;
×
673
        position.longitude_deg = global_position_int.lon * 1e-7;
×
674
        position.absolute_altitude_m = global_position_int.alt * 1e-3f;
×
675
        position.relative_altitude_m = global_position_int.relative_alt * 1e-3f;
×
676
        set_position(position);
×
677
    }
678

679
    {
680
        Telemetry::VelocityNed velocity;
×
681
        velocity.north_m_s = global_position_int.vx * 1e-2f;
×
682
        velocity.east_m_s = global_position_int.vy * 1e-2f;
×
683
        velocity.down_m_s = global_position_int.vz * 1e-2f;
×
684
        set_velocity_ned(velocity);
×
685
    }
686

687
    {
688
        Telemetry::Heading heading;
×
689
        heading.heading_deg = (global_position_int.hdg != std::numeric_limits<uint16_t>::max()) ?
×
690
                                  static_cast<double>(global_position_int.hdg) * 1e-2 :
×
691
                                  static_cast<double>(NAN);
692
        set_heading(heading);
×
693
    }
694

695
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
696
    _position_subscriptions.queue(
×
697
        position(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
698

699
    _velocity_ned_subscriptions.queue(
×
700
        velocity_ned(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
701

702
    _heading_subscriptions.queue(
×
703
        heading(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
704
}
×
705

706
void TelemetryImpl::process_home_position(const mavlink_message_t& message)
×
707
{
708
    mavlink_home_position_t home_position;
×
709
    mavlink_msg_home_position_decode(&message, &home_position);
×
710
    Telemetry::Position new_pos;
×
711
    new_pos.latitude_deg = home_position.latitude * 1e-7;
×
712
    new_pos.longitude_deg = home_position.longitude * 1e-7;
×
713
    new_pos.absolute_altitude_m = home_position.altitude * 1e-3f;
×
714
    new_pos.relative_altitude_m = 0.0f; // 0 by definition.
×
715

716
    set_home_position(new_pos);
×
717

718
    set_health_home_position(true);
×
719

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

725
void TelemetryImpl::process_attitude(const mavlink_message_t& message)
×
726
{
727
    mavlink_attitude_t attitude;
×
728
    mavlink_msg_attitude_decode(&message, &attitude);
×
729

730
    Telemetry::EulerAngle euler_angle;
×
731
    euler_angle.roll_deg = to_deg_from_rad(attitude.roll);
×
732
    euler_angle.pitch_deg = to_deg_from_rad(attitude.pitch);
×
733
    euler_angle.yaw_deg = to_deg_from_rad(attitude.yaw);
×
734
    euler_angle.timestamp_us = static_cast<uint64_t>(attitude.time_boot_ms) * 1000;
×
735
    set_attitude_euler(euler_angle);
×
736

737
    Telemetry::AngularVelocityBody angular_velocity_body;
×
738
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
739
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
740
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
741
    set_attitude_angular_velocity_body(angular_velocity_body);
×
742

743
    _attitude_euler_angle_subscriptions.queue(
×
744
        attitude_euler(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
745

746
    _attitude_angular_velocity_body_subscriptions.queue(
×
747
        attitude_angular_velocity_body(),
748
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
749
}
×
750

751
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
752
{
753
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
×
754
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
755

756
    Telemetry::Quaternion quaternion;
×
757
    quaternion.w = mavlink_attitude_quaternion.q1;
×
758
    quaternion.x = mavlink_attitude_quaternion.q2;
×
759
    quaternion.y = mavlink_attitude_quaternion.q3;
×
760
    quaternion.z = mavlink_attitude_quaternion.q4;
×
761
    quaternion.timestamp_us =
×
762
        static_cast<uint64_t>(mavlink_attitude_quaternion.time_boot_ms) * 1000;
×
763

764
    Telemetry::AngularVelocityBody angular_velocity_body;
×
765
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
766
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
767
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
768

769
    set_attitude_quaternion(quaternion);
×
770

771
    set_attitude_angular_velocity_body(angular_velocity_body);
×
772

773
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
774
    _attitude_quaternion_angle_subscriptions.queue(attitude_quaternion(), [this](const auto& func) {
×
775
        _system_impl->call_user_callback(func);
×
776
    });
×
777

778
    _attitude_angular_velocity_body_subscriptions.queue(
×
779
        attitude_angular_velocity_body(),
780
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
781
}
×
782

783
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
784
{
785
    mavlink_altitude_t mavlink_altitude;
×
786
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
787

788
    Telemetry::Altitude new_altitude;
×
789
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
790
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
791
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
792
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
793
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
794
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
795

796
    set_altitude(new_altitude);
×
797

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

803
void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message)
×
804
{
805
    mavlink_highres_imu_t highres_imu;
×
806
    mavlink_msg_highres_imu_decode(&message, &highres_imu);
×
807
    Telemetry::Imu new_imu;
×
808
    new_imu.acceleration_frd.forward_m_s2 = highres_imu.xacc;
×
809
    new_imu.acceleration_frd.right_m_s2 = highres_imu.yacc;
×
810
    new_imu.acceleration_frd.down_m_s2 = highres_imu.zacc;
×
811
    new_imu.angular_velocity_frd.forward_rad_s = highres_imu.xgyro;
×
812
    new_imu.angular_velocity_frd.right_rad_s = highres_imu.ygyro;
×
813
    new_imu.angular_velocity_frd.down_rad_s = highres_imu.zgyro;
×
814
    new_imu.magnetic_field_frd.forward_gauss = highres_imu.xmag;
×
815
    new_imu.magnetic_field_frd.right_gauss = highres_imu.ymag;
×
816
    new_imu.magnetic_field_frd.down_gauss = highres_imu.zmag;
×
817
    new_imu.temperature_degc = highres_imu.temperature;
×
818
    new_imu.timestamp_us = highres_imu.time_usec;
×
819

820
    set_imu_reading_ned(new_imu);
×
821

822
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
823
    _imu_reading_ned_subscriptions.queue(
×
824
        imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
825
}
×
826

827
void TelemetryImpl::process_scaled_imu(const mavlink_message_t& message)
×
828
{
829
    mavlink_scaled_imu_t scaled_imu_reading;
×
830
    mavlink_msg_scaled_imu_decode(&message, &scaled_imu_reading);
×
831
    Telemetry::Imu new_imu;
×
832
    new_imu.acceleration_frd.forward_m_s2 = scaled_imu_reading.xacc;
×
833
    new_imu.acceleration_frd.right_m_s2 = scaled_imu_reading.yacc;
×
834
    new_imu.acceleration_frd.down_m_s2 = scaled_imu_reading.zacc;
×
835
    new_imu.angular_velocity_frd.forward_rad_s = scaled_imu_reading.xgyro;
×
836
    new_imu.angular_velocity_frd.right_rad_s = scaled_imu_reading.ygyro;
×
837
    new_imu.angular_velocity_frd.down_rad_s = scaled_imu_reading.zgyro;
×
838
    new_imu.magnetic_field_frd.forward_gauss = scaled_imu_reading.xmag;
×
839
    new_imu.magnetic_field_frd.right_gauss = scaled_imu_reading.ymag;
×
840
    new_imu.magnetic_field_frd.down_gauss = scaled_imu_reading.zmag;
×
841
    new_imu.temperature_degc = static_cast<float>(scaled_imu_reading.temperature) * 1e-2f;
×
842
    new_imu.timestamp_us = static_cast<uint64_t>(scaled_imu_reading.time_boot_ms) * 1000;
×
843

844
    set_scaled_imu(new_imu);
×
845

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

851
void TelemetryImpl::process_raw_imu(const mavlink_message_t& message)
×
852
{
853
    mavlink_raw_imu_t raw_imu_reading;
×
854
    mavlink_msg_raw_imu_decode(&message, &raw_imu_reading);
×
855
    Telemetry::Imu new_imu;
×
856
    new_imu.acceleration_frd.forward_m_s2 = raw_imu_reading.xacc;
×
857
    new_imu.acceleration_frd.right_m_s2 = raw_imu_reading.yacc;
×
858
    new_imu.acceleration_frd.down_m_s2 = raw_imu_reading.zacc;
×
859
    new_imu.angular_velocity_frd.forward_rad_s = raw_imu_reading.xgyro;
×
860
    new_imu.angular_velocity_frd.right_rad_s = raw_imu_reading.ygyro;
×
861
    new_imu.angular_velocity_frd.down_rad_s = raw_imu_reading.zgyro;
×
862
    new_imu.magnetic_field_frd.forward_gauss = raw_imu_reading.xmag;
×
863
    new_imu.magnetic_field_frd.right_gauss = raw_imu_reading.ymag;
×
864
    new_imu.magnetic_field_frd.down_gauss = raw_imu_reading.zmag;
×
865
    new_imu.temperature_degc = static_cast<float>(raw_imu_reading.temperature) * 1e-2f;
×
866
    new_imu.timestamp_us = raw_imu_reading.time_usec;
×
867

868
    set_raw_imu(new_imu);
×
869

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

875
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
×
876
{
877
    mavlink_gps_raw_int_t gps_raw_int;
×
878
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
×
879

880
    Telemetry::FixType fix_type;
881
    switch (gps_raw_int.fix_type) {
×
882
        case 0:
×
883
            fix_type = Telemetry::FixType::NoGps;
×
884
            break;
×
885
        case 1:
×
886
            fix_type = Telemetry::FixType::NoFix;
×
887
            break;
×
888
        case 2:
×
889
            fix_type = Telemetry::FixType::Fix2D;
×
890
            break;
×
891
        case 3:
×
892
            fix_type = Telemetry::FixType::Fix3D;
×
893
            break;
×
894
        case 4:
×
895
            fix_type = Telemetry::FixType::FixDgps;
×
896
            break;
×
897
        case 5:
×
898
            fix_type = Telemetry::FixType::RtkFloat;
×
899
            break;
×
900
        case 6:
×
901
            fix_type = Telemetry::FixType::RtkFixed;
×
902
            break;
×
903

904
        default:
×
905
            LogErr() << "Received unknown GPS fix type!";
×
906
            fix_type = Telemetry::FixType::NoGps;
×
907
            break;
×
908
    }
909

910
    Telemetry::GpsInfo new_gps_info;
×
911
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
912
    new_gps_info.fix_type = fix_type;
×
913
    set_gps_info(new_gps_info);
×
914

915
    Telemetry::RawGps raw_gps_info;
×
916
    raw_gps_info.timestamp_us = gps_raw_int.time_usec;
×
917
    raw_gps_info.latitude_deg = gps_raw_int.lat * 1e-7;
×
918
    raw_gps_info.longitude_deg = gps_raw_int.lon * 1e-7;
×
919
    raw_gps_info.absolute_altitude_m = gps_raw_int.alt * 1e-3f;
×
920
    raw_gps_info.hdop = static_cast<float>(gps_raw_int.eph) * 1e-2f;
×
921
    raw_gps_info.vdop = static_cast<float>(gps_raw_int.epv) * 1e-2f;
×
922
    raw_gps_info.velocity_m_s = static_cast<float>(gps_raw_int.vel) * 1e-2f;
×
923
    raw_gps_info.cog_deg = static_cast<float>(gps_raw_int.cog) * 1e-2f;
×
924
    raw_gps_info.altitude_ellipsoid_m = static_cast<float>(gps_raw_int.alt_ellipsoid) * 1e-3f;
×
925
    raw_gps_info.horizontal_uncertainty_m = static_cast<float>(gps_raw_int.h_acc) * 1e-3f;
×
926
    raw_gps_info.vertical_uncertainty_m = static_cast<float>(gps_raw_int.v_acc) * 1e-3f;
×
927
    raw_gps_info.velocity_uncertainty_m_s = static_cast<float>(gps_raw_int.vel_acc) * 1e-3f;
×
928
    raw_gps_info.heading_uncertainty_deg = static_cast<float>(gps_raw_int.hdg_acc) * 1e-5f;
×
929
    raw_gps_info.yaw_deg = static_cast<float>(gps_raw_int.yaw) * 1e-2f;
×
930
    set_raw_gps(raw_gps_info);
×
931

932
    {
933
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
934
        _gps_info_subscriptions.queue(
×
935
            gps_info(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
936
        _raw_gps_subscriptions.queue(
×
937
            raw_gps(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
938
    }
×
939
}
×
940

941
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
942
{
943
    mavlink_hil_state_quaternion_t hil_state_quaternion;
×
944
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
945

946
    Telemetry::GroundTruth new_ground_truth;
×
947
    new_ground_truth.latitude_deg = hil_state_quaternion.lat * 1e-7;
×
948
    new_ground_truth.longitude_deg = hil_state_quaternion.lon * 1e-7;
×
949
    new_ground_truth.absolute_altitude_m = hil_state_quaternion.alt * 1e-3f;
×
950

951
    set_ground_truth(new_ground_truth);
×
952

953
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
954
    _ground_truth_subscriptions.queue(
×
955
        ground_truth(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
956
}
×
957

958
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
959
{
960
    mavlink_extended_sys_state_t extended_sys_state;
×
961
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
962

963
    {
964
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
965
        set_landed_state(landed_state);
×
966

967
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
968
        set_vtol_state(vtol_state);
×
969
    }
970

971
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
972
    _landed_state_subscriptions.queue(
×
973
        landed_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
974

975
    _vtol_state_subscriptions.queue(
×
976
        vtol_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
977

978
    if (extended_sys_state.landed_state == MAV_LANDED_STATE_IN_AIR ||
×
979
        extended_sys_state.landed_state == MAV_LANDED_STATE_TAKEOFF ||
×
980
        extended_sys_state.landed_state == MAV_LANDED_STATE_LANDING) {
×
981
        set_in_air(true);
×
982
    } else if (extended_sys_state.landed_state == MAV_LANDED_STATE_ON_GROUND) {
×
983
        set_in_air(false);
×
984
    }
985
    // If landed_state is undefined, we use what we have received last.
986

987
    _in_air_subscriptions.queue(
×
988
        in_air(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
989
}
×
990
void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)
×
991
{
992
    mavlink_vfr_hud_t vfr_hud;
×
993
    mavlink_msg_vfr_hud_decode(&message, &vfr_hud);
×
994

995
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
996
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
997
    new_fixedwing_metrics.groundspeed_m_s = vfr_hud.groundspeed;
×
998
    new_fixedwing_metrics.heading_deg = vfr_hud.heading;
×
999
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
1000
    new_fixedwing_metrics.absolute_altitude_m = vfr_hud.alt;
×
1001
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1002

1003
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1004

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

1010
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1011
{
1012
    mavlink_sys_status_t sys_status;
×
1013
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1014

1015
    if (!_has_bat_status) {
×
1016
        Telemetry::Battery new_battery;
×
1017
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1018
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1019

1020
        set_battery(new_battery);
×
1021

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

1029
    const bool rc_ok =
×
1030
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1031

1032
    set_rc_status({rc_ok}, std::nullopt);
×
1033

1034
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1035
        set_health_gyrometer_calibration(
×
1036
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1037
    }
1038

1039
    // PX4 v1.15.3 and previous has the bug that it doesn't set 3D_ACCEL present.
1040
    // Therefore, we ignore that and look at the health flag only.
1041
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL ||
×
1042
        _system_impl->autopilot() == Autopilot::Px4) {
×
1043
        set_health_accelerometer_calibration(
×
1044
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1045
    }
1046

1047
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1048
        set_health_magnetometer_calibration(
×
1049
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1050
    }
1051

1052
    const bool global_position_ok =
1053
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1054

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

1058
    const bool local_position_ok =
1059
        global_position_ok ||
×
1060
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1061
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1062

1063
    set_health_local_position(local_position_ok);
×
1064
    set_health_global_position(global_position_ok);
×
1065

1066
    set_rc_status({rc_ok}, std::nullopt);
×
1067

1068
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1069
    _rc_status_subscriptions.queue(
×
1070
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1071

1072
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1073
    set_health_armable(armable);
×
1074
    _health_all_ok_subscriptions.queue(
×
1075
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1076
}
×
1077

1078
bool TelemetryImpl::sys_status_present_enabled_health(
×
1079
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1080
{
1081
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1082
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1083
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1084
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1085
}
1086

1087
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1088
{
1089
    mavlink_battery_status_t bat_status;
×
1090
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1091

1092
    _has_bat_status = true;
×
1093

1094
    Telemetry::Battery new_battery;
×
1095
    new_battery.id = bat_status.id;
×
1096
    new_battery.temperature_degc = (bat_status.temperature == std::numeric_limits<int16_t>::max()) ?
×
1097
                                       static_cast<float>(NAN) :
1098
                                       bat_status.temperature * 1e-2f; // cdegC to degC
×
1099
    new_battery.voltage_v = 0.0f;
×
1100
    for (int i = 0; i < 10; ++i) {
×
1101
        if (bat_status.voltages[i] == std::numeric_limits<uint16_t>::max()) {
×
1102
            break;
×
1103
        }
1104
        new_battery.voltage_v += static_cast<float>(bat_status.voltages[i]) * 1e-3f;
×
1105
    }
1106

1107
    for (int i = 0; i < 4; ++i) {
×
1108
        if (bat_status.voltages_ext[i] == std::numeric_limits<uint16_t>::max()) {
×
1109
            // Some implementations out there set it to UINT16_MAX to signal invalid.
1110
            // That's not up to the spec but we can ignore it nevertheless to be backwards
1111
            // compatible.
1112
            break;
×
1113
        } else if (bat_status.voltages_ext[i] > 1) {
×
1114
            // A value of 1 means 0 mV.
1115
            new_battery.voltage_v += static_cast<float>(bat_status.voltages_ext[i]) * 1e-3f;
×
1116
        }
1117
    }
1118

1119
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1120
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1121
                                        static_cast<float>(NAN) :
1122
                                        bat_status.current_battery * 1e-2f; // cA to A
×
NEW
1123
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1124
                                           static_cast<float>(NAN) :
NEW
1125
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
NEW
1126
    new_battery.time_remaining_s =
×
UNCOV
1127
        (bat_status.time_remaining == std::numeric_limits<int16_t>::max()) ?
×
1128
            static_cast<float>(NAN) :
NEW
1129
            bat_status.time_remaining;
×
1130

1131
    Telemetry::BatteryFunction battery_function;
NEW
1132
    switch (bat_status.battery_function) {
×
NEW
1133
        case 0:
×
NEW
1134
            battery_function = Telemetry::BatteryFunction::Unknown;
×
NEW
1135
            break;
×
NEW
1136
        case 1:
×
NEW
1137
            battery_function = Telemetry::BatteryFunction::All;
×
NEW
1138
            break;
×
NEW
1139
        case 2:
×
NEW
1140
            battery_function = Telemetry::BatteryFunction::Propulsion;
×
NEW
1141
            break;
×
NEW
1142
        case 3:
×
NEW
1143
            battery_function = Telemetry::BatteryFunction::Avionics;
×
NEW
1144
            break;
×
NEW
1145
        case 4:
×
NEW
1146
            battery_function = Telemetry::BatteryFunction::Payload;
×
NEW
1147
            break;
×
1148

NEW
1149
        default:
×
NEW
1150
            battery_function = Telemetry::BatteryFunction::Unknown;
×
1151
            break;
×
1152
    }
UNCOV
1153
    new_battery.battery_function = battery_function;
×
1154
    set_battery(new_battery);
×
1155

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

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

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

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

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

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

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

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

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

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

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

1226
    set_status_text(new_status_text);
3✔
1227

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

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

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

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

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

1252
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1253

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

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

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

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

1273
    set_actuator_control_target(group, controls);
×
1274

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

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

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

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

1295
    set_actuator_output_status(active, actuators);
×
1296

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

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

1308
    Telemetry::Odometry odometry_struct{};
×
1309

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

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

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

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

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

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

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

1346
    set_odometry(odometry_struct);
×
1347

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

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

1358
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1359

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

1368
    set_distance_sensor(distance_sensor_struct);
×
1369

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

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

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

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

1582
    return euler_angle;
×
1583
}
1584

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

1590
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1591

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

1601
    set_scaled_pressure(scaled_pressure_struct);
×
1602

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

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

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

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

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

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

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

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

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

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

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

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

1725
Telemetry::Position TelemetryImpl::home() const
×
1726
{
1727
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1728
    return _home_position;
×
1729
}
×
1730

1731
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1732
{
1733
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1734
    _home_position = home_position;
×
1735
}
×
1736

1737
bool TelemetryImpl::armed() const
1✔
1738
{
1739
    return _armed;
1✔
1740
}
1741

1742
bool TelemetryImpl::in_air() const
×
1743
{
1744
    return _in_air;
×
1745
}
1746

1747
void TelemetryImpl::set_in_air(bool in_air_new)
×
1748
{
1749
    _in_air = in_air_new;
×
1750
}
×
1751

1752
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1753
{
1754
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1755
    _status_text = status_text;
3✔
1756
}
3✔
1757

1758
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1759
{
1760
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1761
    return _status_text;
3✔
1762
}
3✔
1763

1764
void TelemetryImpl::set_armed(bool armed_new)
1✔
1765
{
1766
    _armed = armed_new;
1✔
1767
}
1✔
1768

1769
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1770
{
1771
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1772
    return _attitude_quaternion;
×
1773
}
×
1774

1775
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1776
{
1777
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1778
    return _attitude_angular_velocity_body;
×
1779
}
×
1780

1781
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1782
{
1783
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1784
    return _ground_truth;
×
1785
}
×
1786

1787
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1788
{
1789
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1790
    return _fixedwing_metrics;
×
1791
}
×
1792

1793
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1794
{
1795
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1796
    return _attitude_euler;
×
1797
}
×
1798

1799
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1800
{
1801
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1802
    _attitude_quaternion = quaternion;
×
1803
}
×
1804

1805
void TelemetryImpl::set_attitude_euler(Telemetry::EulerAngle euler)
×
1806
{
1807
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1808
    _attitude_euler = euler;
×
1809
}
×
1810

1811
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1812
    Telemetry::AngularVelocityBody angular_velocity_body)
1813
{
1814
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1815
    _attitude_angular_velocity_body = angular_velocity_body;
×
1816
}
×
1817

1818
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1819
{
1820
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1821
    _ground_truth = ground_truth;
×
1822
}
×
1823

1824
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1825
{
1826
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1827
    _fixedwing_metrics = fixedwing_metrics;
×
1828
}
×
1829

1830
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1831
{
1832
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1833
    return _velocity_ned;
×
1834
}
×
1835

1836
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1837
{
1838
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1839
    _velocity_ned = velocity_ned;
×
1840
}
×
1841

1842
Telemetry::Imu TelemetryImpl::imu() const
×
1843
{
1844
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1845
    return _imu_reading_ned;
×
1846
}
×
1847

1848
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1849
{
1850
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1851
    _imu_reading_ned = imu_reading_ned;
×
1852
}
×
1853

1854
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
1855
{
1856
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1857
    return _scaled_imu;
×
1858
}
×
1859

1860
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1861
{
1862
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1863
    _scaled_imu = scaled_imu;
×
1864
}
×
1865

1866
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1867
{
1868
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1869
    return _raw_imu;
×
1870
}
×
1871

1872
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1873
{
1874
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1875
    _raw_imu = raw_imu;
×
1876
}
×
1877

1878
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
1879
{
1880
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1881
    return _gps_info;
×
1882
}
×
1883

1884
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
1885
{
1886
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1887
    _gps_info = gps_info;
×
1888
}
×
1889

1890
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
1891
{
1892
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1893
    return _raw_gps;
×
1894
}
×
1895

1896
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
1897
{
1898
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1899
    _raw_gps = raw_gps;
×
1900
}
×
1901

1902
Telemetry::Battery TelemetryImpl::battery() const
×
1903
{
1904
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1905
    return _battery;
×
1906
}
×
1907

1908
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
1909
{
1910
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1911
    _battery = battery;
×
1912
}
×
1913

1914
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1915
{
1916
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
1917
}
1918

1919
Telemetry::Health TelemetryImpl::health() const
1✔
1920
{
1921
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1922
    return _health;
2✔
1923
}
1✔
1924

1925
bool TelemetryImpl::health_all_ok() const
1✔
1926
{
1927
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1928
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
1✔
1929
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
1930
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
1931
        return true;
×
1932
    } else {
1933
        return false;
1✔
1934
    }
1935
}
1✔
1936

1937
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
1938
{
1939
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
1940
    return _rc_status;
×
1941
}
×
1942

1943
uint64_t TelemetryImpl::unix_epoch_time() const
×
1944
{
1945
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
1946
    return _unix_epoch_time_us;
×
1947
}
×
1948

1949
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
1950
{
1951
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
1952
    return _actuator_control_target;
×
1953
}
×
1954

1955
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
1956
{
1957
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
1958
    return _actuator_output_status;
×
1959
}
×
1960

1961
Telemetry::Odometry TelemetryImpl::odometry() const
×
1962
{
1963
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
1964
    return _odometry;
×
1965
}
×
1966

1967
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
1968
{
1969
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
1970
    return _distance_sensor;
×
1971
}
×
1972

1973
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
1974
{
1975
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
1976
    return _scaled_pressure;
×
1977
}
×
1978

1979
void TelemetryImpl::set_health_local_position(bool ok)
×
1980
{
1981
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1982
    _health.is_local_position_ok = ok;
×
1983
}
×
1984

1985
void TelemetryImpl::set_health_global_position(bool ok)
×
1986
{
1987
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1988
    _health.is_global_position_ok = ok;
×
1989
}
×
1990

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

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

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

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

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

2021
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2022
{
2023
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2024
    return _vtol_state;
×
2025
}
×
2026

2027
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2028
{
2029
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2030
    _vtol_state = vtol_state;
×
2031
}
×
2032

2033
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2034
{
2035
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2036
    return _landed_state;
×
2037
}
×
2038

2039
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2040
{
2041
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2042
    _landed_state = landed_state;
×
2043
}
×
2044

2045
void TelemetryImpl::set_rc_status(
×
2046
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2047
{
2048
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2049

2050
    if (maybe_available) {
×
2051
        _rc_status.is_available = maybe_available.value();
×
2052
        if (maybe_available.value()) {
×
2053
            _rc_status.was_available_once = true;
×
2054
        }
2055
    }
2056

2057
    if (maybe_signal_strength_percent) {
×
2058
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2059
    }
2060
}
×
2061

2062
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2063
{
2064
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2065
    _unix_epoch_time_us = time_us;
×
2066
}
×
2067

2068
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2069
{
2070
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2071
    _actuator_control_target.group = group;
×
2072
    _actuator_control_target.controls = controls;
×
2073
}
×
2074

2075
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2076
{
2077
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2078
    _actuator_output_status.active = active;
×
2079
    _actuator_output_status.actuator = actuators;
×
2080
}
×
2081

2082
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2083
{
2084
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2085
    _odometry = odometry;
×
2086
}
×
2087

2088
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2089
{
2090
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2091
    _distance_sensor = distance_sensor;
×
2092
}
×
2093

2094
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2095
{
2096
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2097
    _scaled_pressure = scaled_pressure;
×
2098
}
×
2099

2100
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2101
    const Telemetry::PositionVelocityNedCallback& callback)
2102
{
2103
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2104
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2105
}
×
2106

2107
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2108
{
2109
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2110
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2111
}
×
2112

2113
Telemetry::PositionHandle
2114
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2115
{
2116
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2117
    return _position_subscriptions.subscribe(callback);
×
2118
}
×
2119

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

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

2132
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2133
{
2134
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2135
    _home_position_subscriptions.unsubscribe(handle);
×
2136
}
×
2137

2138
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2139
{
2140
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2141
    return _in_air_subscriptions.subscribe(callback);
×
2142
}
×
2143

2144
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2145
{
2146
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2147
    return _in_air_subscriptions.unsubscribe(handle);
×
2148
}
×
2149

2150
Telemetry::StatusTextHandle
2151
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2152
{
2153
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2154
    return _status_text_subscriptions.subscribe(callback);
2✔
2155
}
2✔
2156

2157
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2158
{
2159
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
2160
    _status_text_subscriptions.unsubscribe(handle);
1✔
2161
}
1✔
2162

2163
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2164
{
2165
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2166
    return _armed_subscriptions.subscribe(callback);
×
2167
}
×
2168

2169
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2170
{
2171
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2172
    _armed_subscriptions.unsubscribe(handle);
×
2173
}
×
2174

2175
Telemetry::AttitudeQuaternionHandle
2176
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2177
{
2178
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2179
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2180
}
×
2181

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

2188
Telemetry::AttitudeEulerHandle
2189
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2190
{
2191
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2192
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2193
}
×
2194

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

2201
Telemetry::AttitudeAngularVelocityBodyHandle
2202
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2203
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2204
{
2205
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2206
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2207
}
×
2208

2209
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2210
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2211
{
2212
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2213
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2214
}
×
2215

2216
Telemetry::FixedwingMetricsHandle
2217
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2218
{
2219
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2220
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2221
}
×
2222

2223
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2224
{
2225
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2226
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2227
}
×
2228

2229
Telemetry::GroundTruthHandle
2230
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2231
{
2232
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2233
    return _ground_truth_subscriptions.subscribe(callback);
×
2234
}
×
2235

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

2242
Telemetry::VelocityNedHandle
2243
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2244
{
2245
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2246
    return _velocity_ned_subscriptions.subscribe(callback);
×
2247
}
×
2248

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

2255
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2256
{
2257
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2258
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2259
}
×
2260

2261
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2262
{
2263
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2264
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2265
}
×
2266

2267
Telemetry::ScaledImuHandle
2268
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2269
{
2270
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2271
    return _scaled_imu_subscriptions.subscribe(callback);
×
2272
}
×
2273

2274
void TelemetryImpl::unsubscribe_scaled_imu(Telemetry::ScaledImuHandle handle)
×
2275
{
2276
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2277
    _scaled_imu_subscriptions.unsubscribe(handle);
×
2278
}
×
2279

2280
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2281
{
2282
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2283
    return _raw_imu_subscriptions.subscribe(callback);
×
2284
}
×
2285

2286
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2287
{
2288
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2289
    _raw_imu_subscriptions.unsubscribe(handle);
×
2290
}
×
2291

2292
Telemetry::GpsInfoHandle
2293
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2294
{
2295
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2296
    return _gps_info_subscriptions.subscribe(callback);
×
2297
}
×
2298

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

2305
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2306
{
2307
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2308
    return _raw_gps_subscriptions.subscribe(callback);
×
2309
}
×
2310

2311
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2312
{
2313
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2314
    _raw_gps_subscriptions.unsubscribe(handle);
×
2315
}
×
2316

2317
Telemetry::BatteryHandle
2318
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2319
{
2320
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2321
    return _battery_subscriptions.subscribe(callback);
×
2322
}
×
2323

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

2330
Telemetry::FlightModeHandle
2331
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2332
{
2333
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2334
    return _flight_mode_subscriptions.subscribe(callback);
×
2335
}
×
2336

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

2343
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2344
{
2345
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2346
    return _health_subscriptions.subscribe(callback);
×
2347
}
×
2348

2349
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2350
{
2351
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2352
    _health_subscriptions.unsubscribe(handle);
×
2353
}
×
2354

2355
Telemetry::HealthAllOkHandle
2356
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2357
{
2358
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2359
    return _health_all_ok_subscriptions.subscribe(callback);
×
2360
}
×
2361

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

2368
Telemetry::VtolStateHandle
2369
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2370
{
2371
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2372
    return _vtol_state_subscriptions.subscribe(callback);
×
2373
}
×
2374

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

2381
Telemetry::LandedStateHandle
2382
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2383
{
2384
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2385
    return _landed_state_subscriptions.subscribe(callback);
×
2386
}
×
2387

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

2394
Telemetry::RcStatusHandle
2395
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2396
{
2397
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2398
    return _rc_status_subscriptions.subscribe(callback);
×
2399
}
×
2400

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

2407
Telemetry::UnixEpochTimeHandle
2408
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2409
{
2410
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2411
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2412
}
×
2413

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

2420
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2421
    const Telemetry::ActuatorControlTargetCallback& callback)
2422
{
2423
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2424
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2425
}
×
2426

2427
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2428
    Telemetry::ActuatorControlTargetHandle handle)
2429
{
2430
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2431
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2432
}
×
2433

2434
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2435
    const Telemetry::ActuatorOutputStatusCallback& callback)
2436
{
2437
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2438
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2439
}
×
2440

2441
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2442
{
2443
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2444
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2445
}
×
2446

2447
Telemetry::OdometryHandle
2448
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2449
{
2450
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2451
    return _odometry_subscriptions.subscribe(callback);
×
2452
}
×
2453

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

2460
Telemetry::DistanceSensorHandle
2461
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2462
{
2463
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2464
    return _distance_sensor_subscriptions.subscribe(callback);
×
2465
}
×
2466

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

2473
Telemetry::ScaledPressureHandle
2474
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2475
{
2476
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2477
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2478
}
×
2479

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

2486
Telemetry::HeadingHandle
2487
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2488
{
2489
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2490
    return _heading_subscriptions.subscribe(callback);
×
2491
}
×
2492

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

2499
Telemetry::AltitudeHandle
2500
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2501
{
2502
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2503
    return _altitude_subscriptions.subscribe(callback);
×
2504
}
×
2505

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

2512
void TelemetryImpl::get_gps_global_origin_async(
×
2513
    const Telemetry::GetGpsGlobalOriginCallback callback)
2514
{
2515
    _system_impl->mavlink_request_message().request(
×
2516
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2517
        MAV_COMP_ID_AUTOPILOT1,
2518
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2519
            if (result == MavlinkCommandSender::Result::Success) {
×
2520
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
×
2521
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2522

2523
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2524
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2525
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2526
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2527
                _system_impl->call_user_callback([callback, gps_global_origin]() {
×
2528
                    callback(Telemetry::Result::Success, gps_global_origin);
2529
                });
2530

2531
            } else {
2532
                _system_impl->call_user_callback([callback, result]() {
×
2533
                    callback(telemetry_result_from_command_result(result), {});
2534
                });
2535
            }
2536
        });
×
2537
}
×
2538

2539
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2540
{
2541
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2542
    auto fut = prom.get_future();
×
2543

2544
    get_gps_global_origin_async(
×
2545
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2546
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2547
        });
×
2548
    return fut.get();
×
2549
}
×
2550

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

© 2026 Coveralls, Inc