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

mavlink / MAVSDK / 4899817366

pending completion
4899817366

Pull #1772

github

GitHub
Merge c0bb90862 into e4e9c71dd
Pull Request #1772: Refactor MAVLinkParameters into client and server classes

2192 of 2192 new or added lines in 34 files covered. (100.0%)

7708 of 24812 relevant lines covered (31.07%)

19.96 hits per line

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

5.13
/src/mavsdk/plugins/telemetry/telemetry_impl.cpp
1
#include "telemetry_impl.h"
2
#include "system.h"
3
#include "math_conversions.h"
4
#include "mavsdk_math.h"
5
#include "callback_list.tpp"
6

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

14
namespace mavsdk {
15

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

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

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

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

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

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

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

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

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

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

91
    _system_impl->register_mavlink_message_handler(
1✔
92
        MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS,
93
        [this](const mavlink_message_t& message) {
×
94
            process_gimbal_device_attitude_status(message);
×
95
        },
×
96
        this);
97

98
    _system_impl->register_mavlink_message_handler(
1✔
99
        MAVLINK_MSG_ID_GPS_RAW_INT,
100
        [this](const mavlink_message_t& message) { process_gps_raw_int(message); },
×
101
        this);
102

103
    _system_impl->register_mavlink_message_handler(
1✔
104
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
105
        [this](const mavlink_message_t& message) { process_extended_sys_state(message); },
×
106
        this);
107

108
    _system_impl->register_mavlink_message_handler(
1✔
109
        MAVLINK_MSG_ID_SYS_STATUS,
110
        [this](const mavlink_message_t& message) { process_sys_status(message); },
×
111
        this);
112

113
    _system_impl->register_mavlink_message_handler(
1✔
114
        MAVLINK_MSG_ID_BATTERY_STATUS,
115
        [this](const mavlink_message_t& message) { process_battery_status(message); },
×
116
        this);
117

118
    _system_impl->register_mavlink_message_handler(
1✔
119
        MAVLINK_MSG_ID_HEARTBEAT,
120
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
×
121
        this);
122

123
    _system_impl->register_mavlink_message_handler(
1✔
124
        MAVLINK_MSG_ID_RC_CHANNELS,
125
        [this](const mavlink_message_t& message) { process_rc_channels(message); },
×
126
        this);
127

128
    _system_impl->register_mavlink_message_handler(
1✔
129
        MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET,
130
        [this](const mavlink_message_t& message) { process_actuator_control_target(message); },
×
131
        this);
132

133
    _system_impl->register_mavlink_message_handler(
1✔
134
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
135
        [this](const mavlink_message_t& message) { process_actuator_output_status(message); },
×
136
        this);
137

138
    _system_impl->register_mavlink_message_handler(
1✔
139
        MAVLINK_MSG_ID_ODOMETRY,
140
        [this](const mavlink_message_t& message) { process_odometry(message); },
×
141
        this);
142

143
    _system_impl->register_mavlink_message_handler(
1✔
144
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
145
        [this](const mavlink_message_t& message) { process_distance_sensor(message); },
×
146
        this);
147

148
    _system_impl->register_mavlink_message_handler(
1✔
149
        MAVLINK_MSG_ID_SCALED_PRESSURE,
150
        [this](const mavlink_message_t& message) { process_scaled_pressure(message); },
×
151
        this);
152

153
    _system_impl->register_mavlink_message_handler(
1✔
154
        MAVLINK_MSG_ID_UTM_GLOBAL_POSITION,
155
        [this](const mavlink_message_t& message) { process_unix_epoch_time(message); },
×
156
        this);
157

158
    _system_impl->register_mavlink_message_handler(
1✔
159
        MAVLINK_MSG_ID_HIGHRES_IMU,
160
        [this](const mavlink_message_t& message) { process_imu_reading_ned(message); },
×
161
        this);
162

163
    _system_impl->register_mavlink_message_handler(
1✔
164
        MAVLINK_MSG_ID_SCALED_IMU,
165
        [this](const mavlink_message_t& message) { process_scaled_imu(message); },
×
166
        this);
167

168
    _system_impl->register_mavlink_message_handler(
1✔
169
        MAVLINK_MSG_ID_RAW_IMU,
170
        [this](const mavlink_message_t& message) { process_raw_imu(message); },
×
171
        this);
172

173
    _system_impl->register_mavlink_message_handler(
1✔
174
        MAVLINK_MSG_ID_VFR_HUD,
175
        [this](const mavlink_message_t& message) { process_fixedwing_metrics(message); },
×
176
        this);
177

178
    _system_impl->register_mavlink_message_handler(
1✔
179
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
180
        [this](const mavlink_message_t& message) { process_ground_truth(message); },
×
181
        this);
182

183
    _system_impl->register_mavlink_message_handler(
1✔
184
        MAVLINK_MSG_ID_ALTITUDE,
185
        [this](const mavlink_message_t& message) { process_altitude(message); },
×
186
        this);
187

188
    _system_impl->register_param_changed_handler(
1✔
189
        [this](const std::string& name) { process_parameter_update(name); }, this);
×
190

191
    _system_impl->register_statustext_handler(
1✔
192
        [this](const MavlinkStatustextHandler::Statustext& statustext) {
3✔
193
            receive_statustext(statustext);
3✔
194
        },
3✔
195
        this);
196
}
1✔
197

198
void TelemetryImpl::deinit()
1✔
199
{
200
    _system_impl->cancel_all_param(this);
1✔
201
    _system_impl->remove_call_every(_calibration_cookie);
1✔
202
    _system_impl->unregister_statustext_handler(this);
1✔
203
    _system_impl->unregister_timeout_handler(_gps_raw_timeout_cookie);
1✔
204
    _system_impl->unregister_timeout_handler(_unix_epoch_timeout_cookie);
1✔
205
    _system_impl->unregister_param_changed_handler(this);
1✔
206
    _system_impl->unregister_all_mavlink_message_handlers(this);
1✔
207

208
    _has_received_gyro_calibration = false;
1✔
209
    _has_received_accel_calibration = false;
1✔
210
    _has_received_mag_calibration = false;
1✔
211

212
    {
213
        std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
1✔
214
        _ap_calibration = {};
1✔
215
    }
216

217
    _sys_status_used_for_position = SysStatusUsed::Unknown;
1✔
218
}
1✔
219

220
void TelemetryImpl::enable()
1✔
221
{
222
    _system_impl->register_timeout_handler(
1✔
223
        [this]() { receive_gps_raw_timeout(); }, 2.0, &_gps_raw_timeout_cookie);
×
224

225
    _system_impl->register_timeout_handler(
1✔
226
        [this]() { receive_unix_epoch_timeout(); }, 2.0, &_unix_epoch_timeout_cookie);
×
227

228
    // FIXME: The calibration check should eventually be better than this.
229
    //        For now, we just do the same as QGC does.
230

231
    _system_impl->add_call_every([this]() { check_calibration(); }, 5.0, &_calibration_cookie);
1✔
232

233
    // We're going to retry until we have the Home Position.
234
    _system_impl->add_call_every(
1✔
235
        [this]() { request_home_position_again(); }, 2.0f, &_homepos_cookie);
×
236
}
1✔
237

238
void TelemetryImpl::disable()
1✔
239
{
240
    _system_impl->remove_call_every(_calibration_cookie);
1✔
241
    _system_impl->remove_call_every(_homepos_cookie);
1✔
242
}
1✔
243

244
void TelemetryImpl::request_home_position_again()
×
245
{
246
    {
247
        std::lock_guard<std::mutex> lock(_request_home_position_mutex);
×
248
        if (_health.is_home_position_ok) {
×
249
            _system_impl->remove_call_every(_homepos_cookie);
×
250
            return;
×
251
        }
252
    }
253
    request_home_position_async();
×
254
}
255

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

262
Telemetry::Result TelemetryImpl::set_rate_position(double rate_hz)
×
263
{
264
    _position_rate_hz = rate_hz;
×
265
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
266

267
    return telemetry_result_from_command_result(
×
268
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
269
}
270

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

277
Telemetry::Result TelemetryImpl::set_rate_in_air(double rate_hz)
×
278
{
279
    return set_rate_landed_state(rate_hz);
×
280
}
281

282
Telemetry::Result TelemetryImpl::set_rate_vtol_state(double rate_hz)
×
283
{
284
    return set_rate_landed_state(rate_hz);
×
285
}
286

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

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

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

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

311
Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz)
×
312
{
313
    _velocity_ned_rate_hz = rate_hz;
×
314
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
315

316
    return telemetry_result_from_command_result(
×
317
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
318
}
319

320
Telemetry::Result TelemetryImpl::set_rate_imu(double rate_hz)
×
321
{
322
    return telemetry_result_from_command_result(
×
323
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIGHRES_IMU, rate_hz));
×
324
}
325

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

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

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

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

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

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

362
Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz)
×
363
{
364
    UNUSED(rate_hz);
×
365
    LogWarn() << "System status is usually fixed at 1 Hz";
×
366
    return Telemetry::Result::Unsupported;
×
367
}
368

369
Telemetry::Result TelemetryImpl::set_rate_actuator_control_target(double rate_hz)
×
370
{
371
    return telemetry_result_from_command_result(
×
372
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, rate_hz));
×
373
}
374

375
Telemetry::Result TelemetryImpl::set_rate_actuator_output_status(double rate_hz)
×
376
{
377
    return telemetry_result_from_command_result(
×
378
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, rate_hz));
×
379
}
380

381
Telemetry::Result TelemetryImpl::set_rate_odometry(double rate_hz)
×
382
{
383
    return telemetry_result_from_command_result(
×
384
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ODOMETRY, rate_hz));
×
385
}
386

387
Telemetry::Result TelemetryImpl::set_rate_distance_sensor(double rate_hz)
×
388
{
389
    return telemetry_result_from_command_result(
×
390
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_DISTANCE_SENSOR, rate_hz));
×
391
}
392

393
Telemetry::Result TelemetryImpl::set_rate_scaled_pressure(double rate_hz)
×
394
{
395
    return telemetry_result_from_command_result(
×
396
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SCALED_PRESSURE, rate_hz));
×
397
}
398

399
Telemetry::Result TelemetryImpl::set_rate_unix_epoch_time(double rate_hz)
×
400
{
401
    return telemetry_result_from_command_result(
×
402
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, rate_hz));
×
403
}
404

405
Telemetry::Result TelemetryImpl::set_rate_altitude(double rate_hz)
×
406
{
407
    return telemetry_result_from_command_result(
×
408
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ALTITUDE, rate_hz));
×
409
}
410

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

422
void TelemetryImpl::set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
423
{
424
    _position_rate_hz = rate_hz;
×
425
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
426

427
    _system_impl->set_msg_rate_async(
×
428
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
429
        max_rate_hz,
430
        [callback](MavlinkCommandSender::Result command_result, float) {
×
431
            command_result_callback(command_result, callback);
×
432
        });
×
433
}
×
434

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

445
void TelemetryImpl::set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
446
{
447
    set_rate_landed_state_async(rate_hz, callback);
×
448
}
×
449

450
void TelemetryImpl::set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
451
{
452
    set_rate_landed_state_async(rate_hz, callback);
×
453
}
×
454

455
void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
456
{
457
    _system_impl->set_msg_rate_async(
×
458
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
459
        rate_hz,
460
        [callback](MavlinkCommandSender::Result command_result, float) {
×
461
            command_result_callback(command_result, callback);
×
462
        });
×
463
}
×
464

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

475
void TelemetryImpl::set_rate_attitude_quaternion_async(
×
476
    double rate_hz, Telemetry::ResultCallback callback)
477
{
478
    _system_impl->set_msg_rate_async(
×
479
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
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_attitude_euler_async(
×
487
    double rate_hz, Telemetry::ResultCallback callback)
488
{
489
    _system_impl->set_msg_rate_async(
×
490
        MAVLINK_MSG_ID_ATTITUDE,
491
        rate_hz,
492
        [callback](MavlinkCommandSender::Result command_result, float) {
×
493
            command_result_callback(command_result, callback);
×
494
        });
×
495
}
×
496

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

508
void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
509
{
510
    _velocity_ned_rate_hz = rate_hz;
×
511
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
512

513
    _system_impl->set_msg_rate_async(
×
514
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
515
        max_rate_hz,
516
        [callback](MavlinkCommandSender::Result command_result, float) {
×
517
            command_result_callback(command_result, callback);
×
518
        });
×
519
}
×
520

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

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

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

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

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

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

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

592
void TelemetryImpl::set_rate_rc_status_async(double rate_hz, Telemetry::ResultCallback callback)
×
593
{
594
    UNUSED(rate_hz);
×
595
    LogWarn() << "System status is usually fixed at 1 Hz";
×
596
    _system_impl->call_user_callback([callback]() { callback(Telemetry::Result::Unsupported); });
×
597
}
×
598

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

610
void TelemetryImpl::set_rate_actuator_control_target_async(
×
611
    double rate_hz, Telemetry::ResultCallback callback)
612
{
613
    _system_impl->set_msg_rate_async(
×
614
        MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET,
615
        rate_hz,
616
        [callback](MavlinkCommandSender::Result command_result, float) {
×
617
            command_result_callback(command_result, callback);
×
618
        });
×
619
}
×
620

621
void TelemetryImpl::set_rate_actuator_output_status_async(
×
622
    double rate_hz, Telemetry::ResultCallback callback)
623
{
624
    _system_impl->set_msg_rate_async(
×
625
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
626
        rate_hz,
627
        [callback](MavlinkCommandSender::Result command_result, float) {
×
628
            command_result_callback(command_result, callback);
×
629
        });
×
630
}
×
631

632
void TelemetryImpl::set_rate_odometry_async(double rate_hz, Telemetry::ResultCallback callback)
×
633
{
634
    _system_impl->set_msg_rate_async(
×
635
        MAVLINK_MSG_ID_ODOMETRY,
636
        rate_hz,
637
        [callback](MavlinkCommandSender::Result command_result, float) {
×
638
            command_result_callback(command_result, callback);
×
639
        });
×
640
}
×
641

642
void TelemetryImpl::set_rate_distance_sensor_async(
×
643
    double rate_hz, Telemetry::ResultCallback callback)
644
{
645
    _system_impl->set_msg_rate_async(
×
646
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
647
        rate_hz,
648
        [callback](MavlinkCommandSender::Result command_result, float) {
×
649
            command_result_callback(command_result, callback);
×
650
        });
×
651
}
×
652

653
void TelemetryImpl::set_rate_scaled_pressure_async(
×
654
    double rate_hz, Telemetry::ResultCallback callback)
655
{
656
    _system_impl->set_msg_rate_async(
×
657
        MAVLINK_MSG_ID_SCALED_PRESSURE,
658
        rate_hz,
659
        [callback](MavlinkCommandSender::Result command_result, float) {
×
660
            command_result_callback(command_result, callback);
×
661
        });
×
662
}
×
663

664
Telemetry::Result
665
TelemetryImpl::telemetry_result_from_command_result(MavlinkCommandSender::Result command_result)
×
666
{
667
    switch (command_result) {
×
668
        case MavlinkCommandSender::Result::Success:
×
669
            return Telemetry::Result::Success;
×
670
        case MavlinkCommandSender::Result::NoSystem:
×
671
            return Telemetry::Result::NoSystem;
×
672
        case MavlinkCommandSender::Result::ConnectionError:
×
673
            return Telemetry::Result::ConnectionError;
×
674
        case MavlinkCommandSender::Result::Busy:
×
675
            return Telemetry::Result::Busy;
×
676
        case MavlinkCommandSender::Result::Denied:
×
677
            // FALLTHROUGH
678
        case MavlinkCommandSender::Result::TemporarilyRejected:
679
            return Telemetry::Result::CommandDenied;
×
680
        case MavlinkCommandSender::Result::Timeout:
×
681
            return Telemetry::Result::Timeout;
×
682
        case MavlinkCommandSender::Result::Unsupported:
×
683
            return Telemetry::Result::Unsupported;
×
684
        default:
×
685
            return Telemetry::Result::Unknown;
×
686
    }
687
}
688

689
void TelemetryImpl::command_result_callback(
×
690
    MavlinkCommandSender::Result command_result, const Telemetry::ResultCallback& callback)
691
{
692
    Telemetry::Result action_result = telemetry_result_from_command_result(command_result);
×
693

694
    callback(action_result);
×
695
}
×
696

697
void TelemetryImpl::process_position_velocity_ned(const mavlink_message_t& message)
×
698
{
699
    mavlink_local_position_ned_t local_position;
×
700
    mavlink_msg_local_position_ned_decode(&message, &local_position);
×
701

702
    Telemetry::PositionVelocityNed position_velocity;
×
703
    position_velocity.position.north_m = local_position.x;
×
704
    position_velocity.position.east_m = local_position.y;
×
705
    position_velocity.position.down_m = local_position.z;
×
706
    position_velocity.velocity.north_m_s = local_position.vx;
×
707
    position_velocity.velocity.east_m_s = local_position.vy;
×
708
    position_velocity.velocity.down_m_s = local_position.vz;
×
709

710
    set_position_velocity_ned(position_velocity);
×
711

712
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
713
    _position_velocity_ned_subscriptions.queue(position_velocity_ned(), [this](const auto& func) {
×
714
        _system_impl->call_user_callback(func);
×
715
    });
×
716

717
    set_health_local_position(true);
×
718
}
×
719

720
void TelemetryImpl::process_global_position_int(const mavlink_message_t& message)
×
721
{
722
    mavlink_global_position_int_t global_position_int;
×
723
    mavlink_msg_global_position_int_decode(&message, &global_position_int);
×
724

725
    {
726
        Telemetry::Position position;
×
727
        position.latitude_deg = global_position_int.lat * 1e-7;
×
728
        position.longitude_deg = global_position_int.lon * 1e-7;
×
729
        position.absolute_altitude_m = global_position_int.alt * 1e-3f;
×
730
        position.relative_altitude_m = global_position_int.relative_alt * 1e-3f;
×
731
        set_position(position);
×
732
    }
733

734
    {
735
        Telemetry::VelocityNed velocity;
×
736
        velocity.north_m_s = global_position_int.vx * 1e-2f;
×
737
        velocity.east_m_s = global_position_int.vy * 1e-2f;
×
738
        velocity.down_m_s = global_position_int.vz * 1e-2f;
×
739
        set_velocity_ned(velocity);
×
740
    }
741

742
    {
743
        Telemetry::Heading heading;
×
744
        heading.heading_deg = (global_position_int.hdg != std::numeric_limits<uint16_t>::max()) ?
×
745
                                  static_cast<double>(global_position_int.hdg) * 1e-2 :
×
746
                                  static_cast<double>(NAN);
747
        set_heading(heading);
×
748
    }
749

750
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
751
    _position_subscriptions.queue(
×
752
        position(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
753

754
    _velocity_ned_subscriptions.queue(
×
755
        velocity_ned(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
756

757
    _heading_subscriptions.queue(
×
758
        heading(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
759
}
×
760

761
void TelemetryImpl::process_home_position(const mavlink_message_t& message)
×
762
{
763
    mavlink_home_position_t home_position;
×
764
    mavlink_msg_home_position_decode(&message, &home_position);
×
765
    Telemetry::Position new_pos;
×
766
    new_pos.latitude_deg = home_position.latitude * 1e-7;
×
767
    new_pos.longitude_deg = home_position.longitude * 1e-7;
×
768
    new_pos.absolute_altitude_m = home_position.altitude * 1e-3f;
×
769
    new_pos.relative_altitude_m = 0.0f; // 0 by definition.
×
770

771
    set_home_position(new_pos);
×
772

773
    set_health_home_position(true);
×
774

775
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
776
    _home_position_subscriptions.queue(
×
777
        home(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
778
}
×
779

780
void TelemetryImpl::process_attitude(const mavlink_message_t& message)
×
781
{
782
    mavlink_attitude_t attitude;
×
783
    mavlink_msg_attitude_decode(&message, &attitude);
×
784

785
    Telemetry::EulerAngle euler_angle;
×
786
    euler_angle.roll_deg = to_deg_from_rad(attitude.roll);
×
787
    euler_angle.pitch_deg = to_deg_from_rad(attitude.pitch);
×
788
    euler_angle.yaw_deg = to_deg_from_rad(attitude.yaw);
×
789
    euler_angle.timestamp_us = static_cast<uint64_t>(attitude.time_boot_ms) * 1000;
×
790

791
    Telemetry::AngularVelocityBody angular_velocity_body;
×
792
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
793
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
794
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
795
    set_attitude_angular_velocity_body(angular_velocity_body);
×
796

797
    _attitude_euler_angle_subscriptions.queue(
×
798
        attitude_euler(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
799

800
    _attitude_angular_velocity_body_subscriptions.queue(
×
801
        attitude_angular_velocity_body(),
802
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
803
}
×
804

805
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
806
{
807
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
×
808
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
809

810
    Telemetry::Quaternion quaternion;
×
811
    quaternion.w = mavlink_attitude_quaternion.q1;
×
812
    quaternion.x = mavlink_attitude_quaternion.q2;
×
813
    quaternion.y = mavlink_attitude_quaternion.q3;
×
814
    quaternion.z = mavlink_attitude_quaternion.q4;
×
815
    quaternion.timestamp_us =
×
816
        static_cast<uint64_t>(mavlink_attitude_quaternion.time_boot_ms) * 1000;
×
817

818
    Telemetry::AngularVelocityBody angular_velocity_body;
×
819
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
820
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
821
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
822

823
    set_attitude_quaternion(quaternion);
×
824

825
    set_attitude_angular_velocity_body(angular_velocity_body);
×
826

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

832
    _attitude_angular_velocity_body_subscriptions.queue(
×
833
        attitude_angular_velocity_body(),
834
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
835
}
×
836

837
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
838
{
839
    mavlink_altitude_t mavlink_altitude;
×
840
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
841

842
    Telemetry::Altitude new_altitude;
×
843
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
844
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
845
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
846
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
847
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
848
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
849

850
    set_altitude(new_altitude);
×
851

852
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
853
    _altitude_subscriptions.queue(
×
854
        altitude(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
855
}
×
856

857
void TelemetryImpl::process_mount_orientation(const mavlink_message_t& message)
×
858
{
859
    // TODO: remove this one once we move all the way to gimbal v2 protocol
860
    mavlink_mount_orientation_t mount_orientation;
×
861
    mavlink_msg_mount_orientation_decode(&message, &mount_orientation);
×
862

863
    Telemetry::EulerAngle euler_angle;
×
864
    euler_angle.roll_deg = mount_orientation.roll;
×
865
    euler_angle.pitch_deg = mount_orientation.pitch;
×
866
    euler_angle.yaw_deg = mount_orientation.yaw_absolute;
×
867

868
    set_camera_attitude_euler_angle(euler_angle);
×
869

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

875
    _camera_attitude_euler_angle_subscriptions.queue(
×
876
        camera_attitude_euler(),
877
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
878
}
×
879

880
void TelemetryImpl::process_gimbal_device_attitude_status(const mavlink_message_t& message)
×
881
{
882
    // We accept both MOUNT_ORIENTATION and GIMBAL_DEVICE_ATTITUDE_STATUS for now,
883
    // in order to support both gimbal v1 and v2 protocols.
884

885
    mavlink_gimbal_device_attitude_status_t attitude_status;
×
886
    mavlink_msg_gimbal_device_attitude_status_decode(&message, &attitude_status);
×
887

888
    Telemetry::Quaternion q;
×
889
    q.w = attitude_status.q[0];
×
890
    q.x = attitude_status.q[1];
×
891
    q.y = attitude_status.q[2];
×
892
    q.z = attitude_status.q[3];
×
893

894
    Telemetry::EulerAngle euler_angle = to_euler_angle_from_quaternion(q);
×
895

896
    set_camera_attitude_euler_angle(euler_angle);
×
897

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

903
    _camera_attitude_euler_angle_subscriptions.queue(
×
904
        camera_attitude_euler(),
905
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
906
}
×
907

908
void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message)
×
909
{
910
    mavlink_highres_imu_t highres_imu;
×
911
    mavlink_msg_highres_imu_decode(&message, &highres_imu);
×
912
    Telemetry::Imu new_imu;
×
913
    new_imu.acceleration_frd.forward_m_s2 = highres_imu.xacc;
×
914
    new_imu.acceleration_frd.right_m_s2 = highres_imu.yacc;
×
915
    new_imu.acceleration_frd.down_m_s2 = highres_imu.zacc;
×
916
    new_imu.angular_velocity_frd.forward_rad_s = highres_imu.xgyro;
×
917
    new_imu.angular_velocity_frd.right_rad_s = highres_imu.ygyro;
×
918
    new_imu.angular_velocity_frd.down_rad_s = highres_imu.zgyro;
×
919
    new_imu.magnetic_field_frd.forward_gauss = highres_imu.xmag;
×
920
    new_imu.magnetic_field_frd.right_gauss = highres_imu.ymag;
×
921
    new_imu.magnetic_field_frd.down_gauss = highres_imu.zmag;
×
922
    new_imu.temperature_degc = highres_imu.temperature;
×
923
    new_imu.timestamp_us = highres_imu.time_usec;
×
924

925
    set_imu_reading_ned(new_imu);
×
926

927
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
928
    _imu_reading_ned_subscriptions.queue(
×
929
        imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
930
}
×
931

932
void TelemetryImpl::process_scaled_imu(const mavlink_message_t& message)
×
933
{
934
    mavlink_scaled_imu_t scaled_imu_reading;
×
935
    mavlink_msg_scaled_imu_decode(&message, &scaled_imu_reading);
×
936
    Telemetry::Imu new_imu;
×
937
    new_imu.acceleration_frd.forward_m_s2 = scaled_imu_reading.xacc;
×
938
    new_imu.acceleration_frd.right_m_s2 = scaled_imu_reading.yacc;
×
939
    new_imu.acceleration_frd.down_m_s2 = scaled_imu_reading.zacc;
×
940
    new_imu.angular_velocity_frd.forward_rad_s = scaled_imu_reading.xgyro;
×
941
    new_imu.angular_velocity_frd.right_rad_s = scaled_imu_reading.ygyro;
×
942
    new_imu.angular_velocity_frd.down_rad_s = scaled_imu_reading.zgyro;
×
943
    new_imu.magnetic_field_frd.forward_gauss = scaled_imu_reading.xmag;
×
944
    new_imu.magnetic_field_frd.right_gauss = scaled_imu_reading.ymag;
×
945
    new_imu.magnetic_field_frd.down_gauss = scaled_imu_reading.zmag;
×
946
    new_imu.temperature_degc = static_cast<float>(scaled_imu_reading.temperature) * 1e-2f;
×
947
    new_imu.timestamp_us = static_cast<uint64_t>(scaled_imu_reading.time_boot_ms) * 1000;
×
948

949
    set_scaled_imu(new_imu);
×
950

951
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
952
    _scaled_imu_subscriptions.queue(
×
953
        scaled_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
954
}
×
955

956
void TelemetryImpl::process_raw_imu(const mavlink_message_t& message)
×
957
{
958
    mavlink_raw_imu_t raw_imu_reading;
×
959
    mavlink_msg_raw_imu_decode(&message, &raw_imu_reading);
×
960
    Telemetry::Imu new_imu;
×
961
    new_imu.acceleration_frd.forward_m_s2 = raw_imu_reading.xacc;
×
962
    new_imu.acceleration_frd.right_m_s2 = raw_imu_reading.yacc;
×
963
    new_imu.acceleration_frd.down_m_s2 = raw_imu_reading.zacc;
×
964
    new_imu.angular_velocity_frd.forward_rad_s = raw_imu_reading.xgyro;
×
965
    new_imu.angular_velocity_frd.right_rad_s = raw_imu_reading.ygyro;
×
966
    new_imu.angular_velocity_frd.down_rad_s = raw_imu_reading.zgyro;
×
967
    new_imu.magnetic_field_frd.forward_gauss = raw_imu_reading.xmag;
×
968
    new_imu.magnetic_field_frd.right_gauss = raw_imu_reading.ymag;
×
969
    new_imu.magnetic_field_frd.down_gauss = raw_imu_reading.zmag;
×
970
    new_imu.temperature_degc = static_cast<float>(raw_imu_reading.temperature) * 1e-2f;
×
971
    new_imu.timestamp_us = raw_imu_reading.time_usec;
×
972

973
    set_raw_imu(new_imu);
×
974

975
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
976
    _raw_imu_subscriptions.queue(
×
977
        raw_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
978
}
×
979

980
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
×
981
{
982
    mavlink_gps_raw_int_t gps_raw_int;
×
983
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
×
984

985
    Telemetry::FixType fix_type;
986
    switch (gps_raw_int.fix_type) {
×
987
        case 0:
×
988
            fix_type = Telemetry::FixType::NoGps;
×
989
            break;
×
990
        case 1:
×
991
            fix_type = Telemetry::FixType::NoFix;
×
992
            break;
×
993
        case 2:
×
994
            fix_type = Telemetry::FixType::Fix2D;
×
995
            break;
×
996
        case 3:
×
997
            fix_type = Telemetry::FixType::Fix3D;
×
998
            break;
×
999
        case 4:
×
1000
            fix_type = Telemetry::FixType::FixDgps;
×
1001
            break;
×
1002
        case 5:
×
1003
            fix_type = Telemetry::FixType::RtkFloat;
×
1004
            break;
×
1005
        case 6:
×
1006
            fix_type = Telemetry::FixType::RtkFixed;
×
1007
            break;
×
1008

1009
        default:
×
1010
            LogErr() << "Received unknown GPS fix type!";
×
1011
            fix_type = Telemetry::FixType::NoGps;
×
1012
            break;
×
1013
    }
1014

1015
    Telemetry::GpsInfo new_gps_info;
×
1016
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
1017
    new_gps_info.fix_type = fix_type;
×
1018
    set_gps_info(new_gps_info);
×
1019

1020
    Telemetry::RawGps raw_gps_info;
×
1021
    raw_gps_info.timestamp_us = gps_raw_int.time_usec;
×
1022
    raw_gps_info.latitude_deg = gps_raw_int.lat * 1e-7;
×
1023
    raw_gps_info.longitude_deg = gps_raw_int.lon * 1e-7;
×
1024
    raw_gps_info.absolute_altitude_m = gps_raw_int.alt * 1e-3f;
×
1025
    raw_gps_info.hdop = static_cast<float>(gps_raw_int.eph) * 1e-2f;
×
1026
    raw_gps_info.vdop = static_cast<float>(gps_raw_int.epv) * 1e-2f;
×
1027
    raw_gps_info.velocity_m_s = static_cast<float>(gps_raw_int.vel) * 1e-2f;
×
1028
    raw_gps_info.cog_deg = static_cast<float>(gps_raw_int.cog) * 1e-2f;
×
1029
    raw_gps_info.altitude_ellipsoid_m = static_cast<float>(gps_raw_int.alt_ellipsoid) * 1e-3f;
×
1030
    raw_gps_info.horizontal_uncertainty_m = static_cast<float>(gps_raw_int.h_acc) * 1e-3f;
×
1031
    raw_gps_info.vertical_uncertainty_m = static_cast<float>(gps_raw_int.v_acc) * 1e-3f;
×
1032
    raw_gps_info.velocity_uncertainty_m_s = static_cast<float>(gps_raw_int.vel_acc) * 1e-3f;
×
1033
    raw_gps_info.heading_uncertainty_deg = static_cast<float>(gps_raw_int.hdg_acc) * 1e-5f;
×
1034
    raw_gps_info.yaw_deg = static_cast<float>(gps_raw_int.yaw) * 1e-2f;
×
1035
    set_raw_gps(raw_gps_info);
×
1036

1037
    if (_sys_status_used_for_position == SysStatusUsed::No) {
×
1038
        // This is just a fallback if sys_status does not contain the appropriate flags yet.
1039
        const bool gps_ok = ((gps_raw_int.fix_type >= 3) && (gps_raw_int.satellites_visible >= 8));
×
1040

1041
        set_health_global_position(gps_ok);
×
1042
    }
1043

1044
    {
1045
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1046
        _gps_info_subscriptions.queue(
×
1047
            gps_info(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1048
        _raw_gps_subscriptions.queue(
×
1049
            raw_gps(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1050
    }
1051

1052
    _system_impl->refresh_timeout_handler(_gps_raw_timeout_cookie);
×
1053
}
×
1054

1055
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
1056
{
1057
    mavlink_hil_state_quaternion_t hil_state_quaternion;
×
1058
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
1059

1060
    Telemetry::GroundTruth new_ground_truth;
×
1061
    new_ground_truth.latitude_deg = hil_state_quaternion.lat * 1e-7;
×
1062
    new_ground_truth.longitude_deg = hil_state_quaternion.lon * 1e-7;
×
1063
    new_ground_truth.absolute_altitude_m = hil_state_quaternion.alt * 1e-3f;
×
1064

1065
    set_ground_truth(new_ground_truth);
×
1066

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

1072
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
1073
{
1074
    mavlink_extended_sys_state_t extended_sys_state;
×
1075
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
1076

1077
    {
1078
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
1079
        set_landed_state(landed_state);
×
1080

1081
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
1082
        set_vtol_state(vtol_state);
×
1083
    }
1084

1085
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1086
    _landed_state_subscriptions.queue(
×
1087
        landed_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1088

1089
    _vtol_state_subscriptions.queue(
×
1090
        vtol_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1091

1092
    if (extended_sys_state.landed_state == MAV_LANDED_STATE_IN_AIR ||
×
1093
        extended_sys_state.landed_state == MAV_LANDED_STATE_TAKEOFF ||
×
1094
        extended_sys_state.landed_state == MAV_LANDED_STATE_LANDING) {
×
1095
        set_in_air(true);
×
1096
    } else if (extended_sys_state.landed_state == MAV_LANDED_STATE_ON_GROUND) {
×
1097
        set_in_air(false);
×
1098
    }
1099
    // If landed_state is undefined, we use what we have received last.
1100

1101
    _in_air_subscriptions.queue(
×
1102
        in_air(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1103
}
×
1104
void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)
×
1105
{
1106
    mavlink_vfr_hud_t vfr_hud;
×
1107
    mavlink_msg_vfr_hud_decode(&message, &vfr_hud);
×
1108

1109
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
1110
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
1111
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
1112
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1113

1114
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1115

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

1121
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1122
{
1123
    mavlink_sys_status_t sys_status;
×
1124
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1125

1126
    if (!_has_bat_status) {
×
1127
        Telemetry::Battery new_battery;
×
1128
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1129
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1130

1131
        set_battery(new_battery);
×
1132

1133
        {
1134
            std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1135
            _battery_subscriptions.queue(
×
1136
                battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1137
        }
1138
    }
1139

1140
    const bool rc_ok =
×
1141
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1142

1143
    set_rc_status({rc_ok}, std::nullopt);
×
1144

1145
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1146
        set_health_gyrometer_calibration(
×
1147
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1148
    } else {
1149
        // If the flag is not supported yet, we fall back to the param.
1150
    }
1151

1152
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL) {
×
1153
        set_health_accelerometer_calibration(
×
1154
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1155
    } else {
1156
        // If the flag is not supported yet, we fall back to the param.
1157
    }
1158

1159
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1160
        set_health_magnetometer_calibration(
×
1161
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1162
    } else {
1163
        // If the flag is not supported yet, we fall back to the param.
1164
    }
1165

1166
    const bool global_position_ok =
1167
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1168

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

1172
    const bool local_position_ok =
1173
        global_position_ok ||
×
1174
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1175
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1176

1177
    set_health_local_position(local_position_ok);
×
1178
    set_health_global_position(global_position_ok);
×
1179

1180
    // If any of these sensors were marked present, we don't have to fall back to check for
1181
    // satellite count.
1182
    _sys_status_used_for_position =
×
1183
        ((sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_GPS) != 0 ||
×
1184
         (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) != 0 ||
×
1185
         (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_VISION_POSITION) !=
×
1186
             0) ?
1187
            SysStatusUsed::Yes :
1188
            SysStatusUsed::No;
1189

1190
    set_rc_status({rc_ok}, std::nullopt);
×
1191

1192
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1193
    _rc_status_subscriptions.queue(
×
1194
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1195

1196
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1197
    set_health_armable(armable);
×
1198
    _health_all_ok_subscriptions.queue(
×
1199
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1200
}
×
1201

1202
bool TelemetryImpl::sys_status_present_enabled_health(
×
1203
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1204
{
1205
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1206
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1207
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1208
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1209
}
1210

1211
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1212
{
1213
    mavlink_battery_status_t bat_status;
×
1214
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1215

1216
    _has_bat_status = true;
×
1217

1218
    Telemetry::Battery new_battery;
×
1219
    new_battery.id = bat_status.id;
×
1220
    new_battery.temperature_degc = (bat_status.temperature == std::numeric_limits<int16_t>::max()) ?
×
1221
                                       static_cast<float>(NAN) :
1222
                                       bat_status.temperature * 1e-2f; // cdegC to degC
×
1223
    new_battery.voltage_v = 0.0f;
×
1224
    for (int i = 0; i < 255; i++) {
×
1225
        if (bat_status.voltages[i] == std::numeric_limits<uint16_t>::max())
×
1226
            break;
×
1227
        new_battery.voltage_v += static_cast<float>(bat_status.voltages[i]) * 1e-3f;
×
1228
    }
1229
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1230
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1231
                                        static_cast<float>(NAN) :
1232
                                        bat_status.current_battery * 1e-2f; // cA to A
×
1233
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1234
                                           static_cast<float>(NAN) :
1235
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
1236

1237
    set_battery(new_battery);
×
1238

1239
    {
1240
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1241
        _battery_subscriptions.queue(
×
1242
            battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1243
    }
1244
}
×
1245

1246
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
×
1247
{
1248
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
×
1249
        return;
×
1250
    }
1251

1252
    mavlink_heartbeat_t heartbeat;
×
1253
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
×
1254

1255
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
×
1256

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

1261
    _flight_mode_subscriptions.queue(
×
1262
        telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode()),
×
1263
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1264

1265
    _health_subscriptions.queue(
×
1266
        health(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1267

1268
    _health_all_ok_subscriptions.queue(
×
1269
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1270
}
1271

1272
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1273
{
1274
    Telemetry::StatusText new_status_text;
6✔
1275

1276
    switch (statustext.severity) {
3✔
1277
        case MAV_SEVERITY_EMERGENCY:
×
1278
            new_status_text.type = Telemetry::StatusTextType::Emergency;
×
1279
            break;
×
1280
        case MAV_SEVERITY_ALERT:
×
1281
            new_status_text.type = Telemetry::StatusTextType::Alert;
×
1282
            break;
×
1283
        case MAV_SEVERITY_CRITICAL:
×
1284
            new_status_text.type = Telemetry::StatusTextType::Critical;
×
1285
            break;
×
1286
        case MAV_SEVERITY_ERROR:
×
1287
            new_status_text.type = Telemetry::StatusTextType::Error;
×
1288
            break;
×
1289
        case MAV_SEVERITY_WARNING:
×
1290
            new_status_text.type = Telemetry::StatusTextType::Warning;
×
1291
            break;
×
1292
        case MAV_SEVERITY_NOTICE:
×
1293
            new_status_text.type = Telemetry::StatusTextType::Notice;
×
1294
            break;
×
1295
        case MAV_SEVERITY_INFO:
3✔
1296
            new_status_text.type = Telemetry::StatusTextType::Info;
3✔
1297
            break;
3✔
1298
        case MAV_SEVERITY_DEBUG:
×
1299
            new_status_text.type = Telemetry::StatusTextType::Debug;
×
1300
            break;
×
1301
        default:
×
1302
            LogWarn() << "Unknown StatusText severity";
×
1303
            new_status_text.type = Telemetry::StatusTextType::Info;
×
1304
            break;
×
1305
    }
1306

1307
    new_status_text.text = statustext.text;
3✔
1308

1309
    set_status_text(new_status_text);
3✔
1310

1311
    std::lock_guard<std::mutex> lock(_subscription_mutex);
6✔
1312
    _status_text_subscriptions.queue(
9✔
1313
        status_text(), [this](const auto& func) { _system_impl->call_user_callback(func); });
11✔
1314
}
3✔
1315

1316
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1317
{
1318
    mavlink_rc_channels_t rc_channels;
×
1319
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1320

1321
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1322
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1323
    }
1324

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

1329
    _system_impl->refresh_timeout_handler(_rc_channels_timeout_cookie);
×
1330
}
×
1331

1332
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1333
{
1334
    mavlink_utm_global_position_t utm_global_position;
×
1335
    mavlink_msg_utm_global_position_decode(&message, &utm_global_position);
×
1336

1337
    set_unix_epoch_time_us(utm_global_position.time);
×
1338

1339
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1340
    _unix_epoch_time_subscriptions.queue(
×
1341
        unix_epoch_time(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1342

1343
    _system_impl->refresh_timeout_handler(_unix_epoch_timeout_cookie);
×
1344
}
×
1345

1346
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1347
{
1348
    mavlink_set_actuator_control_target_t target;
×
1349
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1350

1351
    uint32_t group = target.group_mlx;
×
1352
    std::vector<float> controls;
×
1353

1354
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1355
    // Can't use std::copy because target is packed.
1356
    for (std::size_t i = 0; i < control_size; ++i) {
×
1357
        controls.push_back(target.controls[i]);
×
1358
    }
1359

1360
    set_actuator_control_target(group, controls);
×
1361

1362
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1363
    _actuator_control_target_subscriptions.queue(
×
1364
        actuator_control_target(),
×
1365
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1366
}
×
1367

1368
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1369
{
1370
    mavlink_actuator_output_status_t status;
×
1371
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1372

1373
    uint32_t active = status.active;
×
1374
    std::vector<float> actuators;
×
1375

1376
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1377
    // Can't use std::copy because status is packed.
1378
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1379
        actuators.push_back(status.actuator[i]);
×
1380
    }
1381

1382
    set_actuator_output_status(active, actuators);
×
1383

1384
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1385
    _actuator_output_status_subscriptions.queue(actuator_output_status(), [this](const auto& func) {
×
1386
        _system_impl->call_user_callback(func);
×
1387
    });
×
1388
}
×
1389

1390
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1391
{
1392
    mavlink_odometry_t odometry_msg;
×
1393
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1394

1395
    Telemetry::Odometry odometry_struct{};
×
1396

1397
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1398
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1399
    odometry_struct.child_frame_id =
×
1400
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1401

1402
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1403
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1404
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1405

1406
    odometry_struct.q.w = odometry_msg.q[0];
×
1407
    odometry_struct.q.x = odometry_msg.q[1];
×
1408
    odometry_struct.q.y = odometry_msg.q[2];
×
1409
    odometry_struct.q.z = odometry_msg.q[3];
×
1410

1411
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1412
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1413
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1414

1415
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1416
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1417
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1418

1419
    const std::size_t len_pose_covariance =
×
1420
        sizeof(odometry_msg.pose_covariance) / sizeof(odometry_msg.pose_covariance[0]);
1421
    for (std::size_t i = 0; i < len_pose_covariance; ++i) {
×
1422
        odometry_struct.pose_covariance.covariance_matrix.push_back(
×
1423
            odometry_msg.pose_covariance[i]);
×
1424
    }
1425

1426
    const std::size_t len_velocity_covariance =
×
1427
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1428
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1429
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1430
            odometry_msg.velocity_covariance[i]);
×
1431
    }
1432

1433
    set_odometry(odometry_struct);
×
1434

1435
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1436
    _odometry_subscriptions.queue(
×
1437
        odometry(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1438
}
×
1439

1440
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1441
{
1442
    mavlink_distance_sensor_t distance_sensor_msg;
×
1443
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1444

1445
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1446

1447
    distance_sensor_struct.minimum_distance_m =
×
1448
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1449
    distance_sensor_struct.maximum_distance_m =
×
1450
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1451
    distance_sensor_struct.current_distance_m =
×
1452
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1453

1454
    set_distance_sensor(distance_sensor_struct);
×
1455

1456
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1457
    _distance_sensor_subscriptions.queue(
×
1458
        distance_sensor(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1459
}
×
1460

1461
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1462
{
1463
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1464
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1465

1466
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1467

1468
    scaled_pressure_struct.timestamp_us =
×
1469
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1470
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1471
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1472
    scaled_pressure_struct.temperature_deg =
×
1473
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1474
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1475
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1476

1477
    set_scaled_pressure(scaled_pressure_struct);
×
1478

1479
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1480
    _scaled_pressure_subscriptions.queue(
×
1481
        scaled_pressure(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1482
}
×
1483

1484
Telemetry::LandedState
1485
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1486
{
1487
    switch (extended_sys_state.landed_state) {
×
1488
        case MAV_LANDED_STATE_IN_AIR:
×
1489
            return Telemetry::LandedState::InAir;
×
1490
        case MAV_LANDED_STATE_TAKEOFF:
×
1491
            return Telemetry::LandedState::TakingOff;
×
1492
        case MAV_LANDED_STATE_LANDING:
×
1493
            return Telemetry::LandedState::Landing;
×
1494
        case MAV_LANDED_STATE_ON_GROUND:
×
1495
            return Telemetry::LandedState::OnGround;
×
1496
        default:
×
1497
            return Telemetry::LandedState::Unknown;
×
1498
    }
1499
}
1500

1501
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1502
{
1503
    switch (extended_sys_state.vtol_state) {
×
1504
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1505
            return Telemetry::VtolState::TransitionToFw;
×
1506
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1507
            return Telemetry::VtolState::TransitionToMc;
×
1508
        case MAV_VTOL_STATE_MC:
×
1509
            return Telemetry::VtolState::Mc;
×
1510
        case MAV_VTOL_STATE_FW:
×
1511
            return Telemetry::VtolState::Fw;
×
1512
        default:
×
1513
            return Telemetry::VtolState::Undefined;
×
1514
    }
1515
}
1516

1517
Telemetry::FlightMode TelemetryImpl::telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
×
1518
{
1519
    switch (flight_mode) {
×
1520
        case FlightMode::Ready:
×
1521
            return Telemetry::FlightMode::Ready;
×
1522
        case FlightMode::Takeoff:
×
1523
            return Telemetry::FlightMode::Takeoff;
×
1524
        case FlightMode::Hold:
×
1525
            return Telemetry::FlightMode::Hold;
×
1526
        case FlightMode::Mission:
×
1527
            return Telemetry::FlightMode::Mission;
×
1528
        case FlightMode::ReturnToLaunch:
×
1529
            return Telemetry::FlightMode::ReturnToLaunch;
×
1530
        case FlightMode::Land:
×
1531
            return Telemetry::FlightMode::Land;
×
1532
        case FlightMode::Offboard:
×
1533
            return Telemetry::FlightMode::Offboard;
×
1534
        case FlightMode::FollowMe:
×
1535
            return Telemetry::FlightMode::FollowMe;
×
1536
        case FlightMode::Manual:
×
1537
            return Telemetry::FlightMode::Manual;
×
1538
        case FlightMode::Posctl:
×
1539
            return Telemetry::FlightMode::Posctl;
×
1540
        case FlightMode::Altctl:
×
1541
            return Telemetry::FlightMode::Altctl;
×
1542
        case FlightMode::Rattitude:
×
1543
            return Telemetry::FlightMode::Rattitude;
×
1544
        case FlightMode::Acro:
×
1545
            return Telemetry::FlightMode::Acro;
×
1546
        case FlightMode::Stabilized:
×
1547
            return Telemetry::FlightMode::Stabilized;
×
1548
        default:
×
1549
            return Telemetry::FlightMode::Unknown;
×
1550
    }
1551
}
1552

1553
void TelemetryImpl::receive_param_cal_gyro(MavlinkParameterSender::Result result, int value)
×
1554
{
1555
    if (result != MavlinkParameterSender::Result::Success) {
×
1556
        LogErr() << "Error: Param for gyro cal failed.";
×
1557
        return;
×
1558
    }
1559

1560
    bool ok = (value != 0);
×
1561
    set_health_gyrometer_calibration(ok);
×
1562
}
1563

1564
void TelemetryImpl::receive_param_cal_accel(MavlinkParameterSender::Result result, int value)
×
1565
{
1566
    if (result != MavlinkParameterSender::Result::Success) {
×
1567
        LogErr() << "Error: Param for accel cal failed.";
×
1568
        return;
×
1569
    }
1570

1571
    bool ok = (value != 0);
×
1572
    set_health_accelerometer_calibration(ok);
×
1573
}
1574

1575
void TelemetryImpl::receive_param_cal_mag(MavlinkParameterSender::Result result, int value)
×
1576
{
1577
    if (result != MavlinkParameterSender::Result::Success) {
×
1578
        LogErr() << "Error: Param for mag cal failed.";
×
1579
        return;
×
1580
    }
1581

1582
    bool ok = (value != 0);
×
1583
    set_health_magnetometer_calibration(ok);
×
1584
}
1585

1586
void TelemetryImpl::receive_param_cal_mag_offset_x(
×
1587
    MavlinkParameterSender::Result result, float value)
1588
{
1589
    if (result != MavlinkParameterSender::Result::Success) {
×
1590
        LogErr() << "Error: Param for mag offset_x failed.";
×
1591
        return;
×
1592
    }
1593

1594
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1595
    _ap_calibration.mag_offset.x = {value};
×
1596
    if (_ap_calibration.mag_offset.received_all()) {
×
1597
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1598
    }
1599
}
1600

1601
void TelemetryImpl::receive_param_cal_mag_offset_y(
×
1602
    MavlinkParameterSender::Result result, float value)
1603
{
1604
    if (result != MavlinkParameterSender::Result::Success) {
×
1605
        LogErr() << "Error: Param for mag offset_y failed.";
×
1606
        return;
×
1607
    }
1608

1609
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1610
    _ap_calibration.mag_offset.y = {value};
×
1611
    if (_ap_calibration.mag_offset.received_all()) {
×
1612
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1613
    }
1614
}
1615

1616
void TelemetryImpl::receive_param_cal_mag_offset_z(
×
1617
    MavlinkParameterSender::Result result, float value)
1618
{
1619
    if (result != MavlinkParameterSender::Result::Success) {
×
1620
        LogErr() << "Error: Param for mag offset_z failed.";
×
1621
        return;
×
1622
    }
1623

1624
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1625
    _ap_calibration.mag_offset.z = {value};
×
1626
    if (_ap_calibration.mag_offset.received_all()) {
×
1627
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1628
    }
1629
}
1630

1631
void TelemetryImpl::receive_param_cal_accel_offset_x(
×
1632
    MavlinkParameterSender::Result result, float value)
1633
{
1634
    if (result != MavlinkParameterSender::Result::Success) {
×
1635
        LogErr() << "Error: Param for accel offset_x failed.";
×
1636
        return;
×
1637
    }
1638

1639
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1640
    _ap_calibration.accel_offset.x = {value};
×
1641
    if (_ap_calibration.accel_offset.received_all()) {
×
1642
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1643
    }
1644
}
1645

1646
void TelemetryImpl::receive_param_cal_accel_offset_y(
×
1647
    MavlinkParameterSender::Result result, float value)
1648
{
1649
    if (result != MavlinkParameterSender::Result::Success) {
×
1650
        LogErr() << "Error: Param for accel offset_y failed.";
×
1651
        return;
×
1652
    }
1653

1654
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1655
    _ap_calibration.accel_offset.y = {value};
×
1656
    if (_ap_calibration.accel_offset.received_all()) {
×
1657
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1658
    }
1659
}
1660

1661
void TelemetryImpl::receive_param_cal_accel_offset_z(
×
1662
    MavlinkParameterSender::Result result, float value)
1663
{
1664
    if (result != MavlinkParameterSender::Result::Success) {
×
1665
        LogErr() << "Error: Param for accel offset_z failed.";
×
1666
        return;
×
1667
    }
1668

1669
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1670
    _ap_calibration.accel_offset.z = {value};
×
1671
    if (_ap_calibration.accel_offset.received_all()) {
×
1672
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1673
    }
1674
}
1675

1676
void TelemetryImpl::receive_param_cal_gyro_offset_x(
×
1677
    MavlinkParameterSender::Result result, float value)
1678
{
1679
    if (result != MavlinkParameterSender::Result::Success) {
×
1680
        LogErr() << "Error: Param for gyro offset_x failed.";
×
1681
        return;
×
1682
    }
1683

1684
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1685
    _ap_calibration.gyro_offset.x = {value};
×
1686
    if (_ap_calibration.gyro_offset.received_all()) {
×
1687
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1688
    }
1689
}
1690

1691
void TelemetryImpl::receive_param_cal_gyro_offset_y(
×
1692
    MavlinkParameterSender::Result result, float value)
1693
{
1694
    if (result != MavlinkParameterSender::Result::Success) {
×
1695
        LogErr() << "Error: Param for gyro offset_y failed.";
×
1696
        return;
×
1697
    }
1698

1699
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1700
    _ap_calibration.gyro_offset.y = {value};
×
1701
    if (_ap_calibration.gyro_offset.received_all()) {
×
1702
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1703
    }
1704
}
1705

1706
void TelemetryImpl::receive_param_cal_gyro_offset_z(
×
1707
    MavlinkParameterSender::Result result, float value)
1708
{
1709
    if (result != MavlinkParameterSender::Result::Success) {
×
1710
        LogErr() << "Error: Param for gyro offset_z failed.";
×
1711
        return;
×
1712
    }
1713

1714
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1715
    _ap_calibration.gyro_offset.z = {value};
×
1716
    if (_ap_calibration.gyro_offset.received_all()) {
×
1717
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1718
    }
1719
}
1720

1721
void TelemetryImpl::receive_param_hitl(MavlinkParameterSender::Result result, int value)
×
1722
{
1723
    if (result != MavlinkParameterSender::Result::Success) {
×
1724
        LogErr() << "Error: Param to determine hitl failed.";
×
1725
        return;
×
1726
    }
1727

1728
    _hitl_enabled = (value > 0);
×
1729

1730
    // assume sensor calibration ok in hitl
1731
    if (_hitl_enabled) {
×
1732
        set_health_accelerometer_calibration(true);
×
1733
        set_health_gyrometer_calibration(true);
×
1734
        set_health_magnetometer_calibration(true);
×
1735
    }
1736
    _has_received_hitl_param = true;
×
1737
}
1738

1739
void TelemetryImpl::receive_gps_raw_timeout()
×
1740
{
1741
    if (_sys_status_used_for_position == SysStatusUsed::No) {
×
1742
        const bool position_ok = false;
×
1743
        set_health_local_position(position_ok);
×
1744
        set_health_global_position(position_ok);
×
1745
    }
1746
}
×
1747

1748
void TelemetryImpl::receive_unix_epoch_timeout()
×
1749
{
1750
    const uint64_t unix_epoch = 0;
×
1751
    set_unix_epoch_time_us(unix_epoch);
×
1752
}
×
1753

1754
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1755
{
1756
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1757
    return _position_velocity_ned;
×
1758
}
1759

1760
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1761
{
1762
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1763
    _position_velocity_ned = position_velocity_ned;
×
1764
}
×
1765

1766
Telemetry::Position TelemetryImpl::position() const
×
1767
{
1768
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1769
    return _position;
×
1770
}
1771

1772
void TelemetryImpl::set_position(Telemetry::Position position)
×
1773
{
1774
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1775
    _position = position;
×
1776
}
×
1777

1778
Telemetry::Heading TelemetryImpl::heading() const
×
1779
{
1780
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1781
    return _heading;
×
1782
}
1783

1784
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
1785
{
1786
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1787
    _heading = heading;
×
1788
}
×
1789

1790
Telemetry::Altitude TelemetryImpl::altitude() const
×
1791
{
1792
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1793
    return _altitude;
×
1794
}
1795

1796
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
1797
{
1798
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1799
    _altitude = altitude;
×
1800
}
×
1801

1802
Telemetry::Position TelemetryImpl::home() const
×
1803
{
1804
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1805
    return _home_position;
×
1806
}
1807

1808
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1809
{
1810
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1811
    _home_position = home_position;
×
1812
}
×
1813

1814
bool TelemetryImpl::armed() const
×
1815
{
1816
    return _armed;
×
1817
}
1818

1819
bool TelemetryImpl::in_air() const
×
1820
{
1821
    return _in_air;
×
1822
}
1823

1824
void TelemetryImpl::set_in_air(bool in_air_new)
×
1825
{
1826
    _in_air = in_air_new;
×
1827
}
×
1828

1829
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1830
{
1831
    std::lock_guard<std::mutex> lock(_status_text_mutex);
6✔
1832
    _status_text = status_text;
3✔
1833
}
3✔
1834

1835
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1836
{
1837
    std::lock_guard<std::mutex> lock(_status_text_mutex);
6✔
1838
    return _status_text;
3✔
1839
}
1840

1841
void TelemetryImpl::set_armed(bool armed_new)
×
1842
{
1843
    _armed = armed_new;
×
1844
}
×
1845

1846
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1847
{
1848
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1849
    return _attitude_quaternion;
×
1850
}
1851

1852
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1853
{
1854
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1855
    return _attitude_angular_velocity_body;
×
1856
}
1857

1858
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1859
{
1860
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1861
    return _ground_truth;
×
1862
}
1863

1864
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1865
{
1866
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1867
    return _fixedwing_metrics;
×
1868
}
1869

1870
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1871
{
1872
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1873
    Telemetry::EulerAngle euler = to_euler_angle_from_quaternion(_attitude_quaternion);
×
1874

1875
    return euler;
×
1876
}
1877

1878
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1879
{
1880
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1881
    _attitude_quaternion = quaternion;
×
1882
}
×
1883

1884
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1885
    Telemetry::AngularVelocityBody angular_velocity_body)
1886
{
1887
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1888
    _attitude_angular_velocity_body = angular_velocity_body;
×
1889
}
×
1890

1891
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1892
{
1893
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1894
    _ground_truth = ground_truth;
×
1895
}
×
1896

1897
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1898
{
1899
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1900
    _fixedwing_metrics = fixedwing_metrics;
×
1901
}
×
1902

1903
Telemetry::Quaternion TelemetryImpl::camera_attitude_quaternion() const
×
1904
{
1905
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
1906
    Telemetry::Quaternion quaternion = to_quaternion_from_euler_angle(_camera_attitude_euler_angle);
×
1907

1908
    return quaternion;
×
1909
}
1910

1911
Telemetry::EulerAngle TelemetryImpl::camera_attitude_euler() const
×
1912
{
1913
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
1914

1915
    return _camera_attitude_euler_angle;
×
1916
}
1917

1918
void TelemetryImpl::set_camera_attitude_euler_angle(Telemetry::EulerAngle euler_angle)
×
1919
{
1920
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
1921
    _camera_attitude_euler_angle = euler_angle;
×
1922
}
×
1923

1924
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1925
{
1926
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1927
    return _velocity_ned;
×
1928
}
1929

1930
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1931
{
1932
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1933
    _velocity_ned = velocity_ned;
×
1934
}
×
1935

1936
Telemetry::Imu TelemetryImpl::imu() const
×
1937
{
1938
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1939
    return _imu_reading_ned;
×
1940
}
1941

1942
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1943
{
1944
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1945
    _imu_reading_ned = imu_reading_ned;
×
1946
}
×
1947

1948
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
1949
{
1950
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1951
    return _scaled_imu;
×
1952
}
1953

1954
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1955
{
1956
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1957
    _scaled_imu = scaled_imu;
×
1958
}
×
1959

1960
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1961
{
1962
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1963
    return _raw_imu;
×
1964
}
1965

1966
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1967
{
1968
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1969
    _raw_imu = raw_imu;
×
1970
}
×
1971

1972
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
1973
{
1974
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1975
    return _gps_info;
×
1976
}
1977

1978
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
1979
{
1980
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1981
    _gps_info = gps_info;
×
1982
}
×
1983

1984
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
1985
{
1986
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1987
    return _raw_gps;
×
1988
}
1989

1990
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
1991
{
1992
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1993
    _raw_gps = raw_gps;
×
1994
}
×
1995

1996
Telemetry::Battery TelemetryImpl::battery() const
×
1997
{
1998
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1999
    return _battery;
×
2000
}
2001

2002
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
2003
{
2004
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
2005
    _battery = battery;
×
2006
}
×
2007

2008
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
2009
{
2010
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
2011
}
2012

2013
Telemetry::Health TelemetryImpl::health() const
×
2014
{
2015
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2016
    return _health;
×
2017
}
2018

2019
bool TelemetryImpl::health_all_ok() const
×
2020
{
2021
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2022
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
×
2023
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
2024
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
2025
        return true;
×
2026
    } else {
2027
        return false;
×
2028
    }
2029
}
2030

2031
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
2032
{
2033
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2034
    return _rc_status;
×
2035
}
2036

2037
uint64_t TelemetryImpl::unix_epoch_time() const
×
2038
{
2039
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2040
    return _unix_epoch_time_us;
×
2041
}
2042

2043
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
2044
{
2045
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2046
    return _actuator_control_target;
×
2047
}
2048

2049
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
2050
{
2051
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2052
    return _actuator_output_status;
×
2053
}
2054

2055
Telemetry::Odometry TelemetryImpl::odometry() const
×
2056
{
2057
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2058
    return _odometry;
×
2059
}
2060

2061
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
2062
{
2063
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2064
    return _distance_sensor;
×
2065
}
2066

2067
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
2068
{
2069
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2070
    return _scaled_pressure;
×
2071
}
2072

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

2079
void TelemetryImpl::set_health_global_position(bool ok)
×
2080
{
2081
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2082
    _health.is_global_position_ok = ok;
×
2083
}
×
2084

2085
void TelemetryImpl::set_health_home_position(bool ok)
×
2086
{
2087
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2088
    _health.is_home_position_ok = ok;
×
2089
}
×
2090

2091
void TelemetryImpl::set_health_gyrometer_calibration(bool ok)
×
2092
{
2093
    _has_received_gyro_calibration = true;
×
2094

2095
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2096
    _health.is_gyrometer_calibration_ok = (ok || _hitl_enabled);
×
2097
}
×
2098

2099
void TelemetryImpl::set_health_accelerometer_calibration(bool ok)
×
2100
{
2101
    _has_received_accel_calibration = true;
×
2102

2103
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2104
    _health.is_accelerometer_calibration_ok = (ok || _hitl_enabled);
×
2105
}
×
2106

2107
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
2108
{
2109
    _has_received_mag_calibration = true;
×
2110

2111
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2112
    _health.is_magnetometer_calibration_ok = (ok || _hitl_enabled);
×
2113
}
×
2114

2115
void TelemetryImpl::set_health_armable(bool ok)
×
2116
{
2117
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2118
    _health.is_armable = ok;
×
2119
}
×
2120

2121
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2122
{
2123
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2124
    return _vtol_state;
×
2125
}
2126

2127
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2128
{
2129
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2130
    _vtol_state = vtol_state;
×
2131
}
×
2132

2133
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2134
{
2135
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2136
    return _landed_state;
×
2137
}
2138

2139
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2140
{
2141
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2142
    _landed_state = landed_state;
×
2143
}
×
2144

2145
void TelemetryImpl::set_rc_status(
×
2146
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2147
{
2148
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2149

2150
    if (maybe_available) {
×
2151
        _rc_status.is_available = maybe_available.value();
×
2152
        if (maybe_available.value()) {
×
2153
            _rc_status.was_available_once = true;
×
2154
        }
2155
    }
2156

2157
    if (maybe_signal_strength_percent) {
×
2158
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2159
    }
2160
}
×
2161

2162
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2163
{
2164
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2165
    _unix_epoch_time_us = time_us;
×
2166
}
×
2167

2168
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2169
{
2170
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2171
    _actuator_control_target.group = group;
×
2172
    _actuator_control_target.controls = controls;
×
2173
}
×
2174

2175
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2176
{
2177
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2178
    _actuator_output_status.active = active;
×
2179
    _actuator_output_status.actuator = actuators;
×
2180
}
×
2181

2182
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2183
{
2184
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2185
    _odometry = odometry;
×
2186
}
×
2187

2188
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2189
{
2190
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2191
    _distance_sensor = distance_sensor;
×
2192
}
×
2193

2194
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2195
{
2196
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2197
    _scaled_pressure = scaled_pressure;
×
2198
}
×
2199

2200
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2201
    const Telemetry::PositionVelocityNedCallback& callback)
2202
{
2203
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2204
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2205
}
2206

2207
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2208
{
2209
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2210
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2211
}
×
2212

2213
Telemetry::PositionHandle
2214
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2215
{
2216
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2217
    return _position_subscriptions.subscribe(callback);
×
2218
}
2219

2220
void TelemetryImpl::unsubscribe_position(Telemetry::PositionHandle handle)
×
2221
{
2222
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2223
    _position_subscriptions.unsubscribe(handle);
×
2224
}
×
2225

2226
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2227
{
2228
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2229
    return _home_position_subscriptions.subscribe(callback);
×
2230
}
2231

2232
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2233
{
2234
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2235
    _home_position_subscriptions.unsubscribe(handle);
×
2236
}
×
2237

2238
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2239
{
2240
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2241
    return _in_air_subscriptions.subscribe(callback);
×
2242
}
2243

2244
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2245
{
2246
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2247
    return _in_air_subscriptions.unsubscribe(handle);
×
2248
}
2249

2250
Telemetry::StatusTextHandle
2251
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2252
{
2253
    std::lock_guard<std::mutex> lock(_subscription_mutex);
4✔
2254
    return _status_text_subscriptions.subscribe(callback);
2✔
2255
}
2256

2257
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2258
{
2259
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2260
    _status_text_subscriptions.unsubscribe(handle);
1✔
2261
}
1✔
2262

2263
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2264
{
2265
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2266
    return _armed_subscriptions.subscribe(callback);
×
2267
}
2268

2269
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2270
{
2271
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2272
    _armed_subscriptions.unsubscribe(handle);
×
2273
}
×
2274

2275
Telemetry::AttitudeQuaternionHandle
2276
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2277
{
2278
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2279
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2280
}
2281

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

2288
Telemetry::AttitudeEulerHandle
2289
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2290
{
2291
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2292
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2293
}
2294

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

2301
Telemetry::AttitudeAngularVelocityBodyHandle
2302
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2303
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2304
{
2305
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2306
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2307
}
2308

2309
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2310
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2311
{
2312
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2313
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2314
}
×
2315

2316
Telemetry::FixedwingMetricsHandle
2317
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2318
{
2319
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2320
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2321
}
2322

2323
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2324
{
2325
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2326
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2327
}
×
2328

2329
Telemetry::GroundTruthHandle
2330
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2331
{
2332
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2333
    return _ground_truth_subscriptions.subscribe(callback);
×
2334
}
2335

2336
void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle)
×
2337
{
2338
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2339
    _ground_truth_subscriptions.unsubscribe(handle);
×
2340
}
×
2341

2342
Telemetry::AttitudeQuaternionHandle TelemetryImpl::subscribe_camera_attitude_quaternion(
×
2343
    const Telemetry::AttitudeQuaternionCallback& callback)
2344
{
2345
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2346
    return _camera_attitude_quaternion_subscriptions.subscribe(callback);
×
2347
}
2348

2349
void TelemetryImpl::unsubscribe_camera_attitude_quaternion(
×
2350
    Telemetry::AttitudeQuaternionHandle handle)
2351
{
2352
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2353
    _camera_attitude_quaternion_subscriptions.unsubscribe(handle);
×
2354
}
×
2355

2356
Telemetry::AttitudeEulerHandle
2357
TelemetryImpl::subscribe_camera_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2358
{
2359
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2360
    return _camera_attitude_euler_angle_subscriptions.subscribe(callback);
×
2361
}
2362

2363
void TelemetryImpl::unsubscribe_camera_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2364
{
2365
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2366
    _camera_attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2367
}
×
2368

2369
Telemetry::VelocityNedHandle
2370
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2371
{
2372
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2373
    return _velocity_ned_subscriptions.subscribe(callback);
×
2374
}
2375

2376
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2377
{
2378
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2379
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2380
}
×
2381

2382
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2383
{
2384
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2385
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2386
}
2387

2388
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2389
{
2390
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2391
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2392
}
2393

2394
Telemetry::ScaledImuHandle
2395
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2396
{
2397
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2398
    return _scaled_imu_subscriptions.subscribe(callback);
×
2399
}
2400

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

2407
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2408
{
2409
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2410
    return _raw_imu_subscriptions.subscribe(callback);
×
2411
}
2412

2413
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2414
{
2415
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2416
    _raw_imu_subscriptions.unsubscribe(handle);
×
2417
}
×
2418

2419
Telemetry::GpsInfoHandle
2420
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2421
{
2422
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2423
    return _gps_info_subscriptions.subscribe(callback);
×
2424
}
2425

2426
void TelemetryImpl::unsubscribe_gps_info(Telemetry::GpsInfoHandle handle)
×
2427
{
2428
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2429
    _gps_info_subscriptions.unsubscribe(handle);
×
2430
}
×
2431

2432
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2433
{
2434
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2435
    return _raw_gps_subscriptions.subscribe(callback);
×
2436
}
2437

2438
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2439
{
2440
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2441
    _raw_gps_subscriptions.unsubscribe(handle);
×
2442
}
×
2443

2444
Telemetry::BatteryHandle
2445
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2446
{
2447
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2448
    return _battery_subscriptions.subscribe(callback);
×
2449
}
2450

2451
void TelemetryImpl::unsubscribe_battery(Telemetry::BatteryHandle handle)
×
2452
{
2453
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2454
    _battery_subscriptions.unsubscribe(handle);
×
2455
}
×
2456

2457
Telemetry::FlightModeHandle
2458
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2459
{
2460
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2461
    return _flight_mode_subscriptions.subscribe(callback);
×
2462
}
2463

2464
void TelemetryImpl::unsubscribe_flight_mode(Telemetry::FlightModeHandle handle)
×
2465
{
2466
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2467
    _flight_mode_subscriptions.unsubscribe(handle);
×
2468
}
×
2469

2470
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2471
{
2472
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2473
    return _health_subscriptions.subscribe(callback);
×
2474
}
2475

2476
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2477
{
2478
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2479
    _health_subscriptions.unsubscribe(handle);
×
2480
}
×
2481

2482
Telemetry::HealthAllOkHandle
2483
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2484
{
2485
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2486
    return _health_all_ok_subscriptions.subscribe(callback);
×
2487
}
2488

2489
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2490
{
2491
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2492
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2493
}
×
2494

2495
Telemetry::VtolStateHandle
2496
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2497
{
2498
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2499
    return _vtol_state_subscriptions.subscribe(callback);
×
2500
}
2501

2502
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2503
{
2504
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2505
    _vtol_state_subscriptions.unsubscribe(handle);
×
2506
}
×
2507

2508
Telemetry::LandedStateHandle
2509
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2510
{
2511
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2512
    return _landed_state_subscriptions.subscribe(callback);
×
2513
}
2514

2515
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2516
{
2517
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2518
    _landed_state_subscriptions.unsubscribe(handle);
×
2519
}
×
2520

2521
Telemetry::RcStatusHandle
2522
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2523
{
2524
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2525
    return _rc_status_subscriptions.subscribe(callback);
×
2526
}
2527

2528
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2529
{
2530
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2531
    _rc_status_subscriptions.unsubscribe(handle);
×
2532
}
×
2533

2534
Telemetry::UnixEpochTimeHandle
2535
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2536
{
2537
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2538
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2539
}
2540

2541
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2542
{
2543
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2544
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2545
}
×
2546

2547
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2548
    const Telemetry::ActuatorControlTargetCallback& callback)
2549
{
2550
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2551
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2552
}
2553

2554
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2555
    Telemetry::ActuatorControlTargetHandle handle)
2556
{
2557
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2558
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2559
}
×
2560

2561
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2562
    const Telemetry::ActuatorOutputStatusCallback& callback)
2563
{
2564
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2565
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2566
}
2567

2568
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2569
{
2570
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2571
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2572
}
×
2573

2574
Telemetry::OdometryHandle
2575
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2576
{
2577
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2578
    return _odometry_subscriptions.subscribe(callback);
×
2579
}
2580

2581
void TelemetryImpl::unsubscribe_odometry(Telemetry::OdometryHandle handle)
×
2582
{
2583
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2584
    _odometry_subscriptions.unsubscribe(handle);
×
2585
}
×
2586

2587
Telemetry::DistanceSensorHandle
2588
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2589
{
2590
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2591
    return _distance_sensor_subscriptions.subscribe(callback);
×
2592
}
2593

2594
void TelemetryImpl::unsubscribe_distance_sensor(Telemetry::DistanceSensorHandle handle)
×
2595
{
2596
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2597
    _distance_sensor_subscriptions.unsubscribe(handle);
×
2598
}
×
2599

2600
Telemetry::ScaledPressureHandle
2601
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2602
{
2603
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2604
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2605
}
2606

2607
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2608
{
2609
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2610
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2611
}
×
2612

2613
Telemetry::HeadingHandle
2614
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2615
{
2616
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2617
    return _heading_subscriptions.subscribe(callback);
×
2618
}
2619

2620
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2621
{
2622
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2623
    _heading_subscriptions.unsubscribe(handle);
×
2624
}
×
2625

2626
Telemetry::AltitudeHandle
2627
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2628
{
2629
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2630
    return _altitude_subscriptions.subscribe(callback);
×
2631
}
2632

2633
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2634
{
2635
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2636
    _altitude_subscriptions.unsubscribe(handle);
×
2637
}
×
2638

2639
void TelemetryImpl::request_home_position_async()
×
2640
{
2641
    MavlinkCommandSender::CommandLong command_request_message{};
×
2642
    command_request_message.command = MAV_CMD_REQUEST_MESSAGE;
×
2643
    command_request_message.target_component_id = MAV_COMP_ID_AUTOPILOT1;
×
2644
    command_request_message.params.maybe_param1 = static_cast<float>(MAVLINK_MSG_ID_HOME_POSITION);
×
2645
    _system_impl->send_command_async(command_request_message, nullptr);
×
2646
}
×
2647

2648
void TelemetryImpl::get_gps_global_origin_async(
×
2649
    const Telemetry::GetGpsGlobalOriginCallback callback)
2650
{
2651
    _system_impl->request_message().request(
×
2652
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2653
        MAV_COMP_ID_AUTOPILOT1,
2654
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2655
            if (result == MavlinkCommandSender::Result::Success) {
×
2656
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
×
2657
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2658

2659
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2660
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2661
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2662
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2663
                _system_impl->call_user_callback([callback, gps_global_origin]() {
×
2664
                    callback(Telemetry::Result::Success, gps_global_origin);
2665
                });
2666

2667
            } else {
2668
                _system_impl->call_user_callback([callback, result]() {
×
2669
                    callback(telemetry_result_from_command_result(result), {});
2670
                });
2671
            }
2672
        });
×
2673
}
×
2674

2675
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2676
{
2677
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2678
    auto fut = prom.get_future();
×
2679

2680
    get_gps_global_origin_async(
×
2681
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2682
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2683
        });
×
2684
    return fut.get();
×
2685
}
2686

2687
void TelemetryImpl::check_calibration()
×
2688
{
2689
    {
2690
        std::lock_guard<std::mutex> lock(_health_mutex);
×
2691
        if ((_has_received_gyro_calibration && _has_received_accel_calibration &&
×
2692
             _has_received_mag_calibration) ||
×
2693
            _has_received_hitl_param) {
×
2694
            _system_impl->remove_call_every(_calibration_cookie);
×
2695
            return;
×
2696
        }
2697
    }
2698
    if (_system_impl->has_autopilot()) {
×
2699
        if (_system_impl->autopilot() == SystemImpl::Autopilot::ArduPilot) {
×
2700
            // We need to ask for the home position from ArduPilot
2701
            request_home_position_async();
×
2702

2703
            // ArduPilot calibration sets the offsets,
2704
            // if any offset is 0 the calibration is not complete/unhealthy.
2705
            _system_impl->get_param_float_async(
×
2706
                std::string("INS_GYROFFS_X"),
×
2707
                [this](MavlinkParameterSender::Result result, float value) {
×
2708
                    receive_param_cal_gyro_offset_x(result, value);
×
2709
                },
×
2710
                this);
2711

2712
            _system_impl->get_param_float_async(
×
2713
                std::string("INS_GYROFFS_Y"),
×
2714
                [this](MavlinkParameterSender::Result result, float value) {
×
2715
                    receive_param_cal_gyro_offset_y(result, value);
×
2716
                },
×
2717
                this);
2718

2719
            _system_impl->get_param_float_async(
×
2720
                std::string("INS_GYROFFS_Z"),
×
2721
                [this](MavlinkParameterSender::Result result, float value) {
×
2722
                    receive_param_cal_gyro_offset_z(result, value);
×
2723
                },
×
2724
                this);
2725

2726
            _system_impl->get_param_float_async(
×
2727
                std::string("INS_ACCOFFS_X"),
×
2728
                [this](MavlinkParameterSender::Result result, float value) {
×
2729
                    receive_param_cal_accel_offset_x(result, value);
×
2730
                },
×
2731
                this);
2732

2733
            _system_impl->get_param_float_async(
×
2734
                std::string("INS_ACCOFFS_Y"),
×
2735
                [this](MavlinkParameterSender::Result result, float value) {
×
2736
                    receive_param_cal_accel_offset_y(result, value);
×
2737
                },
×
2738
                this);
2739

2740
            _system_impl->get_param_float_async(
×
2741
                std::string("INS_ACCOFFS_Z"),
×
2742
                [this](MavlinkParameterSender::Result result, float value) {
×
2743
                    receive_param_cal_accel_offset_z(result, value);
×
2744
                },
×
2745
                this);
2746

2747
            _system_impl->get_param_float_async(
×
2748
                std::string("COMPASS_OFS_X"),
×
2749
                [this](MavlinkParameterSender::Result result, float value) {
×
2750
                    receive_param_cal_mag_offset_x(result, value);
×
2751
                },
×
2752
                this);
2753

2754
            _system_impl->get_param_float_async(
×
2755
                std::string("COMPASS_OFS_Y"),
×
2756
                [this](MavlinkParameterSender::Result result, float value) {
×
2757
                    receive_param_cal_mag_offset_y(result, value);
×
2758
                },
×
2759
                this);
2760

2761
            _system_impl->get_param_float_async(
×
2762
                std::string("COMPASS_OFS_Z"),
×
2763
                [this](MavlinkParameterSender::Result result, float value) {
×
2764
                    receive_param_cal_mag_offset_z(result, value);
×
2765
                },
×
2766
                this);
2767

2768
        } else {
2769
            _system_impl->get_param_int_async(
×
2770
                std::string("CAL_GYRO0_ID"),
×
2771
                [this](MavlinkParameterSender::Result result, int32_t value) {
×
2772
                    receive_param_cal_gyro(result, value);
×
2773
                },
×
2774
                this);
2775

2776
            _system_impl->get_param_int_async(
×
2777
                std::string("CAL_ACC0_ID"),
×
2778
                [this](MavlinkParameterSender::Result result, int32_t value) {
×
2779
                    receive_param_cal_accel(result, value);
×
2780
                },
×
2781
                this);
2782

2783
            _system_impl->get_param_int_async(
×
2784
                std::string("CAL_MAG0_ID"),
×
2785
                [this](MavlinkParameterSender::Result result, int32_t value) {
×
2786
                    receive_param_cal_mag(result, value);
×
2787
                },
×
2788
                this);
2789

2790
            _system_impl->get_param_int_async(
×
2791
                std::string("SYS_HITL"),
×
2792
                [this](MavlinkParameterSender::Result result, int32_t value) {
×
2793
                    receive_param_hitl(result, value);
×
2794
                },
×
2795
                this);
2796
        }
2797
    }
2798
}
2799

2800
void TelemetryImpl::process_parameter_update(const std::string& name)
×
2801
{
2802
    if (_system_impl->autopilot() == SystemImpl::Autopilot::ArduPilot) {
×
2803
        if (name.compare("INS_GYROFFS_X") == 0) {
×
2804
            _system_impl->get_param_float_async(
×
2805
                std::string("INS_GYROFFS_X"),
×
2806
                [this](MavlinkParameterSender::Result result, float value) {
×
2807
                    receive_param_cal_gyro_offset_x(result, value);
×
2808
                },
×
2809
                this);
2810
        } else if (name.compare("INS_GYROFFS_Y") == 0) {
×
2811
            _system_impl->get_param_float_async(
×
2812
                std::string("INS_GYROFFS_Y"),
×
2813
                [this](MavlinkParameterSender::Result result, float value) {
×
2814
                    receive_param_cal_gyro_offset_y(result, value);
×
2815
                },
×
2816
                this);
2817
        } else if (name.compare("INS_GYROFFS_Z") == 0) {
×
2818
            _system_impl->get_param_float_async(
×
2819
                std::string("INS_GYROFFS_Z"),
×
2820
                [this](MavlinkParameterSender::Result result, float value) {
×
2821
                    receive_param_cal_gyro_offset_z(result, value);
×
2822
                },
×
2823
                this);
2824
        } else if (name.compare("INS_ACCOFFS_X") == 0) {
×
2825
            _system_impl->get_param_float_async(
×
2826
                std::string("INS_ACCOFFS_X"),
×
2827
                [this](MavlinkParameterSender::Result result, float value) {
×
2828
                    receive_param_cal_accel_offset_x(result, value);
×
2829
                },
×
2830
                this);
2831
        } else if (name.compare("INS_ACCOFFS_Y") == 0) {
×
2832
            _system_impl->get_param_float_async(
×
2833
                std::string("INS_ACCOFFS_Y"),
×
2834
                [this](MavlinkParameterSender::Result result, float value) {
×
2835
                    receive_param_cal_accel_offset_y(result, value);
×
2836
                },
×
2837
                this);
2838
        } else if (name.compare("INS_ACCOFFS_Z") == 0) {
×
2839
            _system_impl->get_param_float_async(
×
2840
                std::string("INS_ACCOFFS_Z"),
×
2841
                [this](MavlinkParameterSender::Result result, float value) {
×
2842
                    receive_param_cal_accel_offset_z(result, value);
×
2843
                },
×
2844
                this);
2845
        } else if (name.compare("COMPASS_OFS_X") == 0) {
×
2846
            _system_impl->get_param_float_async(
×
2847
                std::string("COMPASS_OFS_X"),
×
2848
                [this](MavlinkParameterSender::Result result, float value) {
×
2849
                    receive_param_cal_mag_offset_x(result, value);
×
2850
                },
×
2851
                this);
2852
        } else if (name.compare("COMPASS_OFS_Y") == 0) {
×
2853
            _system_impl->get_param_float_async(
×
2854
                std::string("COMPASS_OFS_Y"),
×
2855
                [this](MavlinkParameterSender::Result result, float value) {
×
2856
                    receive_param_cal_mag_offset_y(result, value);
×
2857
                },
×
2858
                this);
2859
        } else if (name.compare("COMPASS_OFS_Z") == 0) {
×
2860
            _system_impl->get_param_float_async(
×
2861
                std::string("COMPASS_OFS_Z"),
×
2862
                [this](MavlinkParameterSender::Result result, float value) {
×
2863
                    receive_param_cal_mag_offset_z(result, value);
×
2864
                },
×
2865
                this);
2866
        }
2867
    } else {
2868
        if (name.compare("CAL_GYRO0_ID") == 0) {
×
2869
            _system_impl->get_param_int_async(
×
2870
                std::string("CAL_GYRO0_ID"),
×
2871
                [this](MavlinkParameterSender::Result result, int32_t value) {
×
2872
                    receive_param_cal_gyro(result, value);
×
2873
                },
×
2874
                this);
2875

2876
        } else if (name.compare("CAL_ACC0_ID") == 0) {
×
2877
            _system_impl->get_param_int_async(
×
2878
                std::string("CAL_ACC0_ID"),
×
2879
                [this](MavlinkParameterSender::Result result, int32_t value) {
×
2880
                    receive_param_cal_accel(result, value);
×
2881
                },
×
2882
                this);
2883
        } else if (name.compare("CAL_MAG0_ID") == 0) {
×
2884
            _system_impl->get_param_int_async(
×
2885
                std::string("CAL_MAG0_ID"),
×
2886
                [this](MavlinkParameterSender::Result result, int32_t value) {
×
2887
                    receive_param_cal_mag(result, value);
×
2888
                },
×
2889
                this);
2890

2891
        } else if (name.compare("SYS_HITL") == 0) {
×
2892
            _system_impl->get_param_int_async(
×
2893
                std::string("SYS_HITL"),
×
2894
                [this](MavlinkParameterSender::Result result, int32_t value) {
×
2895
                    receive_param_hitl(result, value);
×
2896
                },
×
2897
                this);
2898
        }
2899
    }
2900
}
×
2901

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

© 2025 Coveralls, Inc