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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

0.0
/src/mavsdk/plugins/offboard/offboard_impl.cpp
1
#include <cmath>
2
#include <utility>
3
#include "mavlink_address.h"
4
#include "mavsdk_math.h"
5
#include "offboard_impl.h"
6
#include "mavsdk_impl.h"
7
#include "px4_custom_mode.h"
8

9
namespace mavsdk {
10

11
OffboardImpl::OffboardImpl(System& system) : PluginImplBase(system)
×
12
{
13
    _system_impl->register_plugin(this);
×
14
}
×
15

16
OffboardImpl::OffboardImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
×
17
{
18
    _system_impl->register_plugin(this);
×
19
}
×
20

21
OffboardImpl::~OffboardImpl()
×
22
{
23
    _system_impl->unregister_plugin(this);
×
24
}
×
25

26
void OffboardImpl::init()
×
27
{
28
    _system_impl->register_mavlink_message_handler(
×
29
        MAVLINK_MSG_ID_HEARTBEAT,
30
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
×
31
        this);
32
}
×
33

34
void OffboardImpl::deinit()
×
35
{
36
    {
37
        std::lock_guard<std::mutex> lock(_mutex);
×
38
        stop_sending_setpoints();
×
39
    }
×
40
    _system_impl->unregister_all_mavlink_message_handlers(this);
×
41
}
×
42

43
void OffboardImpl::enable() {}
×
44

45
void OffboardImpl::disable() {}
×
46

47
Offboard::Result OffboardImpl::start()
×
48
{
49
    {
50
        std::lock_guard<std::mutex> lock(_mutex);
×
51
        if (_mode == Mode::NotActive) {
×
52
            return Offboard::Result::NoSetpointSet;
×
53
        }
54
        _last_started = _time.steady_time();
×
55
    }
×
56

57
    return offboard_result_from_command_result(_system_impl->set_flight_mode(FlightMode::Offboard));
×
58
}
59

60
Offboard::Result OffboardImpl::stop()
×
61
{
62
    {
63
        std::lock_guard<std::mutex> lock(_mutex);
×
64
        if (_mode != Mode::NotActive) {
×
65
            stop_sending_setpoints();
×
66
        }
67
    }
×
68

69
    return offboard_result_from_command_result(_system_impl->set_flight_mode(FlightMode::Hold));
×
70
}
71

72
void OffboardImpl::start_async(Offboard::ResultCallback callback)
×
73
{
74
    {
75
        std::lock_guard<std::mutex> lock(_mutex);
×
76

77
        if (_mode == Mode::NotActive) {
×
78
            if (callback) {
×
79
                _system_impl->call_user_callback(
×
80
                    [callback]() { callback(Offboard::Result::NoSetpointSet); });
81
            }
82
            return;
×
83
        }
84
        _last_started = _time.steady_time();
×
85
    }
×
86

87
    _system_impl->set_flight_mode_async(
×
88
        FlightMode::Offboard, [callback, this](MavlinkCommandSender::Result result, float) {
×
89
            receive_command_result(result, callback);
×
90
        });
×
91
}
92

93
void OffboardImpl::stop_async(Offboard::ResultCallback callback)
×
94
{
95
    {
96
        std::lock_guard<std::mutex> lock(_mutex);
×
97
        if (_mode != Mode::NotActive) {
×
98
            stop_sending_setpoints();
×
99
        }
100
    }
×
101

102
    _system_impl->set_flight_mode_async(
×
103
        FlightMode::Hold, [callback, this](MavlinkCommandSender::Result result, float) {
×
104
            receive_command_result(result, callback);
×
105
        });
×
106
}
×
107

108
bool OffboardImpl::is_active()
×
109
{
110
    std::lock_guard<std::mutex> lock(_mutex);
×
111
    return (_mode != Mode::NotActive);
×
112
}
×
113

114
void OffboardImpl::receive_command_result(
×
115
    MavlinkCommandSender::Result result, const Offboard::ResultCallback& callback)
116
{
117
    Offboard::Result offboard_result = offboard_result_from_command_result(result);
×
118
    if (callback) {
×
119
        _system_impl->call_user_callback(
×
120
            [callback, offboard_result]() { callback(offboard_result); });
121
    }
122
}
×
123

124
Offboard::Result OffboardImpl::set_position_ned(Offboard::PositionNedYaw position_ned_yaw)
×
125
{
126
    {
127
        std::lock_guard<std::mutex> lock(_mutex);
×
128
        _position_ned_yaw = position_ned_yaw;
×
129

130
        if (_mode != Mode::PositionNed) {
×
131
            // If we're already sending other setpoints, stop that now.
132
            _system_impl->remove_call_every(_call_every_cookie);
×
133
            // We automatically send Ned setpoints from now on.
134
            _call_every_cookie =
×
135
                _system_impl->add_call_every([this]() { send_position_ned(); }, SEND_INTERVAL_S);
×
136

137
            _mode = Mode::PositionNed;
×
138
        } else {
139
            // We're already sending these kind of setpoints. Since the setpoint change, let's
140
            // reschedule the next call, so we don't send setpoints too often.
141
            _system_impl->reset_call_every(_call_every_cookie);
×
142
        }
143
    }
×
144

145
    // also send it right now to reduce latency
146
    return send_position_ned();
×
147
}
148

149
Offboard::Result OffboardImpl::set_position_global(Offboard::PositionGlobalYaw position_global_yaw)
×
150
{
151
    {
152
        std::lock_guard<std::mutex> lock(_mutex);
×
153
        _position_global_yaw = position_global_yaw;
×
154

155
        if (_mode != Mode::PositionGlobalAltRel) {
×
156
            // If we're already sending other setpoints, stop that now.
157
            _system_impl->remove_call_every(_call_every_cookie);
×
158
            // We automatically send Global setpoints from now on.
159
            _call_every_cookie =
×
160
                _system_impl->add_call_every([this]() { send_position_global(); }, SEND_INTERVAL_S);
×
161

162
            _mode = Mode::PositionGlobalAltRel;
×
163
        } else {
164
            // We're already sending these kind of setpoints. Since the setpoint change, let's
165
            // reschedule the next call, so we don't send setpoints too often.
166
            _system_impl->reset_call_every(_call_every_cookie);
×
167
        }
168
    }
×
169

170
    // also send it right now to reduce latency
171
    return send_position_global();
×
172
}
173

174
Offboard::Result OffboardImpl::set_velocity_ned(Offboard::VelocityNedYaw velocity_ned_yaw)
×
175
{
176
    {
177
        std::lock_guard<std::mutex> lock(_mutex);
×
178
        _velocity_ned_yaw = velocity_ned_yaw;
×
179

180
        if (_mode != Mode::VelocityNed) {
×
181
            // If we're already sending other setpoints, stop that now.
182
            _system_impl->remove_call_every(_call_every_cookie);
×
183
            // We automatically send Ned setpoints from now on.
184
            _call_every_cookie =
×
185
                _system_impl->add_call_every([this]() { send_velocity_ned(); }, SEND_INTERVAL_S);
×
186

187
            _mode = Mode::VelocityNed;
×
188
        } else {
189
            // We're already sending these kind of setpoints. Since the setpoint change, let's
190
            // reschedule the next call, so we don't send setpoints too often.
191
            _system_impl->reset_call_every(_call_every_cookie);
×
192
        }
193
    }
×
194
    // also send it right now to reduce latency
195
    return send_velocity_ned();
×
196
}
197

198
Offboard::Result OffboardImpl::set_position_velocity_ned(
×
199
    Offboard::PositionNedYaw position_ned_yaw, Offboard::VelocityNedYaw velocity_ned_yaw)
200
{
201
    {
202
        std::lock_guard<std::mutex> lock(_mutex);
×
203
        _position_ned_yaw = position_ned_yaw;
×
204
        _velocity_ned_yaw = velocity_ned_yaw;
×
205

206
        if (_mode != Mode::PositionVelocityNed) {
×
207
            // If we're already sending other setpoints, stop that now.
208
            _system_impl->remove_call_every(_call_every_cookie);
×
209
            // We automatically send Ned setpoints from now on.
210
            _call_every_cookie = _system_impl->add_call_every(
×
211
                [this]() { send_position_velocity_ned(); }, SEND_INTERVAL_S);
×
212

213
            _mode = Mode::PositionVelocityNed;
×
214
        } else {
215
            // We're already sending these kind of setpoints. Since the setpoint change, let's
216
            // reschedule the next call, so we don't send setpoints too often.
217
            _system_impl->reset_call_every(_call_every_cookie);
×
218
        }
219
    }
×
220

221
    // also send it right now to reduce latency
222
    return send_position_velocity_ned();
×
223
}
224

225
Offboard::Result OffboardImpl::set_position_velocity_acceleration_ned(
×
226
    Offboard::PositionNedYaw position_ned_yaw,
227
    Offboard::VelocityNedYaw velocity_ned_yaw,
228
    Offboard::AccelerationNed acceleration_ned)
229
{
230
    {
231
        std::lock_guard<std::mutex> lock(_mutex);
×
232
        _position_ned_yaw = position_ned_yaw;
×
233
        _velocity_ned_yaw = velocity_ned_yaw;
×
234
        _acceleration_ned = acceleration_ned;
×
235

236
        if (_mode != Mode::PositionVelocityAccelerationNed) {
×
237
            // If we're already sending other setpoints, stop that now.
238
            _system_impl->remove_call_every(_call_every_cookie);
×
239
            // We automatically send Ned setpoints from now on.
240
            _call_every_cookie = _system_impl->add_call_every(
×
241
                [this]() { send_position_velocity_acceleration_ned(); }, SEND_INTERVAL_S);
×
242

243
            _mode = Mode::PositionVelocityAccelerationNed;
×
244
        } else {
245
            // We're already sending these kind of setpoints. Since the setpoint change, let's
246
            // reschedule the next call, so we don't send setpoints too often.
247
            _system_impl->reset_call_every(_call_every_cookie);
×
248
        }
249
    }
×
250

251
    // also send it right now to reduce latency
252
    return send_position_velocity_acceleration_ned();
×
253
}
254

255
Offboard::Result OffboardImpl::set_acceleration_ned(Offboard::AccelerationNed acceleration_ned)
×
256
{
257
    {
258
        std::lock_guard<std::mutex> lock(_mutex);
×
259
        _acceleration_ned = acceleration_ned;
×
260

261
        if (_mode != Mode::AccelerationNed) {
×
262
            // If we're already sending other setpoints, stop that now.
263
            _system_impl->remove_call_every(_call_every_cookie);
×
264
            // We automatically send Ned setpoints from now on.
265
            _call_every_cookie = _system_impl->add_call_every(
×
266
                [this]() { send_acceleration_ned(); }, SEND_INTERVAL_S);
×
267

268
            _mode = Mode::AccelerationNed;
×
269
        } else {
270
            // We're already sending these kind of setpoints. Since the setpoint change, let's
271
            // reschedule the next call, so we don't send setpoints too often.
272
            _system_impl->reset_call_every(_call_every_cookie);
×
273
        }
274
    }
×
275

276
    // also send it right now to reduce latency
277
    return send_acceleration_ned();
×
278
}
279

280
Offboard::Result
281
OffboardImpl::set_velocity_body(Offboard::VelocityBodyYawspeed velocity_body_yawspeed)
×
282
{
283
    {
284
        std::lock_guard<std::mutex> lock(_mutex);
×
285
        _velocity_body_yawspeed = velocity_body_yawspeed;
×
286

287
        if (_mode != Mode::VelocityBody) {
×
288
            // If we're already sending other setpoints, stop that now.
289
            _system_impl->remove_call_every(_call_every_cookie);
×
290
            // We automatically send body setpoints from now on.
291
            _call_every_cookie =
×
292
                _system_impl->add_call_every([this]() { send_velocity_body(); }, SEND_INTERVAL_S);
×
293

294
            _mode = Mode::VelocityBody;
×
295
        } else {
296
            // We're already sending these kind of setpoints. Since the setpoint change, let's
297
            // reschedule the next call, so we don't send setpoints too often.
298
            _system_impl->reset_call_every(_call_every_cookie);
×
299
        }
300
    }
×
301

302
    // also send it right now to reduce latency
303
    return send_velocity_body();
×
304
}
305

306
Offboard::Result OffboardImpl::set_attitude(Offboard::Attitude attitude)
×
307
{
308
    {
309
        std::lock_guard<std::mutex> lock(_mutex);
×
310
        _attitude = attitude;
×
311

312
        if (_mode != Mode::Attitude) {
×
313
            // If we're already sending other setpoints, stop that now.
314
            _system_impl->remove_call_every(_call_every_cookie);
×
315
            // We automatically send body setpoints from now on.
316
            _call_every_cookie =
×
317
                _system_impl->add_call_every([this]() { send_attitude(); }, SEND_INTERVAL_S);
×
318

319
            _mode = Mode::Attitude;
×
320
        } else {
321
            // We're already sending these kind of setpoints. Since the setpoint change, let's
322
            // reschedule the next call, so we don't send setpoints too often.
323
            _system_impl->reset_call_every(_call_every_cookie);
×
324
        }
325
    }
×
326

327
    // also send it right now to reduce latency
328
    return send_attitude();
×
329
}
330

331
Offboard::Result OffboardImpl::set_attitude_rate(Offboard::AttitudeRate attitude_rate)
×
332
{
333
    {
334
        std::lock_guard<std::mutex> lock(_mutex);
×
335
        _attitude_rate = attitude_rate;
×
336

337
        if (_mode != Mode::AttitudeRate) {
×
338
            // If we're already sending other setpoints, stop that now.
339
            _system_impl->remove_call_every(_call_every_cookie);
×
340
            // We automatically send body setpoints from now on.
341
            _call_every_cookie =
×
342
                _system_impl->add_call_every([this]() { send_attitude_rate(); }, SEND_INTERVAL_S);
×
343

344
            _mode = Mode::AttitudeRate;
×
345
        } else {
346
            // We're already sending these kind of setpoints. Since the setpoint change, let's
347
            // reschedule the next call, so we don't send setpoints too often.
348
            _system_impl->reset_call_every(_call_every_cookie);
×
349
        }
350
    }
×
351

352
    // also send it right now to reduce latency
353
    return send_attitude_rate();
×
354
}
355

356
Offboard::Result OffboardImpl::set_actuator_control(Offboard::ActuatorControl actuator_control)
×
357
{
358
    {
359
        std::lock_guard<std::mutex> lock(_mutex);
×
360
        _actuator_control = actuator_control;
×
361

362
        if (_mode != Mode::ActuatorControl) {
×
363
            // If we're already sending other setpoints, stop that now.
364
            _system_impl->remove_call_every(_call_every_cookie);
×
365
            // We automatically send motor rate values from now on.
366
            _call_every_cookie = _system_impl->add_call_every(
×
367
                [this]() { send_actuator_control(); }, SEND_INTERVAL_S);
×
368

369
            _mode = Mode::ActuatorControl;
×
370
        } else {
371
            // We're already sending these kind of values. Since the value changes, let's
372
            // reschedule the next call, so we don't send values too often.
373
            _system_impl->reset_call_every(_call_every_cookie);
×
374
        }
375
    }
×
376

377
    // It gets sent immediately as part of add_call_every.
378
    return Offboard::Result::Success;
×
379
}
380

381
Offboard::Result OffboardImpl::send_position_ned()
×
382
{
383
    const static uint16_t IGNORE_VX = (1 << 3);
384
    const static uint16_t IGNORE_VY = (1 << 4);
385
    const static uint16_t IGNORE_VZ = (1 << 5);
386
    const static uint16_t IGNORE_AX = (1 << 6);
387
    const static uint16_t IGNORE_AY = (1 << 7);
388
    const static uint16_t IGNORE_AZ = (1 << 8);
389
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
390

391
    const auto position_ned_yaw = [this]() {
×
392
        std::lock_guard<std::mutex> lock(_mutex);
×
393
        return _position_ned_yaw;
×
394
    }();
×
395

396
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
397
        mavlink_message_t message;
398
        mavlink_msg_set_position_target_local_ned_pack_chan(
×
399
            mavlink_address.system_id,
×
400
            mavlink_address.component_id,
×
401
            channel,
402
            &message,
403
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
404
            _system_impl->get_system_id(),
×
405
            _system_impl->get_autopilot_id(),
×
406
            MAV_FRAME_LOCAL_NED,
407
            IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
408
            position_ned_yaw.north_m,
×
409
            position_ned_yaw.east_m,
×
410
            position_ned_yaw.down_m,
×
411
            0.0f, // vx
412
            0.0f, // vy
413
            0.0f, // vz
414
            0.0f, // afx
415
            0.0f, // afy
416
            0.0f, // afz
417
            to_rad_from_deg(position_ned_yaw.yaw_deg), // yaw
×
418
            0.0f); // yaw_rate
419
        return message;
×
420
    }) ?
×
421
               Offboard::Result::Success :
422
               Offboard::Result::ConnectionError;
×
423
}
424

425
Offboard::Result OffboardImpl::send_position_global()
×
426
{
427
    const static uint16_t IGNORE_VX = (1 << 3);
428
    const static uint16_t IGNORE_VY = (1 << 4);
429
    const static uint16_t IGNORE_VZ = (1 << 5);
430
    const static uint16_t IGNORE_AX = (1 << 6);
431
    const static uint16_t IGNORE_AY = (1 << 7);
432
    const static uint16_t IGNORE_AZ = (1 << 8);
433
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
434

435
    const auto position_global_yaw = [this]() {
×
436
        std::lock_guard<std::mutex> lock(_mutex);
×
437
        return _position_global_yaw;
×
438
    }();
×
439

440
    MAV_FRAME frame;
×
441
    switch (position_global_yaw.altitude_type) {
×
442
        case Offboard::PositionGlobalYaw::AltitudeType::Amsl:
×
443
            frame = MAV_FRAME_GLOBAL_INT;
×
444
            break;
×
445
        case Offboard::PositionGlobalYaw::AltitudeType::Agl:
×
446
            frame = MAV_FRAME_GLOBAL_TERRAIN_ALT_INT;
×
447
            break;
×
448
        case Offboard::PositionGlobalYaw::AltitudeType::RelHome:
×
449
            frame = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT;
×
450
            break;
×
451
        default:
×
452
            return Offboard::Result::CommandDenied;
×
453
            break;
454
    }
455
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
456
        mavlink_message_t message;
457
        mavlink_msg_set_position_target_global_int_pack_chan(
×
458
            mavlink_address.system_id,
×
459
            mavlink_address.component_id,
×
460
            channel,
461
            &message,
462
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
463
            _system_impl->get_system_id(),
×
464
            _system_impl->get_autopilot_id(),
×
465
            frame,
×
466
            IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
467
            (int32_t)(position_global_yaw.lat_deg * 1.0e7),
×
468
            (int32_t)(position_global_yaw.lon_deg * 1.0e7),
×
469
            position_global_yaw.alt_m,
×
470
            0.0f, // vx
471
            0.0f, // vy
472
            0.0f, // vz
473
            0.0f, // afx
474
            0.0f, // afy
475
            0.0f, // afz
476
            to_rad_from_deg(position_global_yaw.yaw_deg), // yaw
×
477
            0.0f); // yaw_rate
478
        return message;
×
479
    }) ?
×
480
               Offboard::Result::Success :
481
               Offboard::Result::ConnectionError;
×
482
}
483

484
Offboard::Result OffboardImpl::send_velocity_ned()
×
485
{
486
    const static uint16_t IGNORE_X = (1 << 0);
487
    const static uint16_t IGNORE_Y = (1 << 1);
488
    const static uint16_t IGNORE_Z = (1 << 2);
489
    const static uint16_t IGNORE_AX = (1 << 6);
490
    const static uint16_t IGNORE_AY = (1 << 7);
491
    const static uint16_t IGNORE_AZ = (1 << 8);
492
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
493

494
    const auto velocity_ned_yaw = [this]() {
×
495
        std::lock_guard<std::mutex> lock(_mutex);
×
496
        return _velocity_ned_yaw;
×
497
    }();
×
498

499
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
500
        mavlink_message_t message;
501
        mavlink_msg_set_position_target_local_ned_pack_chan(
×
502
            mavlink_address.system_id,
×
503
            mavlink_address.component_id,
×
504
            channel,
505
            &message,
506
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
507
            _system_impl->get_system_id(),
×
508
            _system_impl->get_autopilot_id(),
×
509
            MAV_FRAME_LOCAL_NED,
510
            IGNORE_X | IGNORE_Y | IGNORE_Z | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
511
            0.0f, // x,
512
            0.0f, // y,
513
            0.0f, // z,
514
            velocity_ned_yaw.north_m_s,
×
515
            velocity_ned_yaw.east_m_s,
×
516
            velocity_ned_yaw.down_m_s,
×
517
            0.0f, // afx
518
            0.0f, // afy
519
            0.0f, // afz
520
            to_rad_from_deg(velocity_ned_yaw.yaw_deg), // yaw
×
521
            0.0f); // yaw_rate
522
        return message;
×
523
    }) ?
×
524
               Offboard::Result::Success :
525
               Offboard::Result::ConnectionError;
×
526
}
527

528
Offboard::Result OffboardImpl::send_position_velocity_ned()
×
529
{
530
    const static uint16_t IGNORE_AX = (1 << 6);
531
    const static uint16_t IGNORE_AY = (1 << 7);
532
    const static uint16_t IGNORE_AZ = (1 << 8);
533
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
534

535
    const auto position_and_velocity = [this]() {
×
536
        std::lock_guard<std::mutex> lock(_mutex);
×
537
        return std::make_pair<>(_position_ned_yaw, _velocity_ned_yaw);
×
538
    }();
×
539

540
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
541
        mavlink_message_t message;
542
        mavlink_msg_set_position_target_local_ned_pack_chan(
×
543
            mavlink_address.system_id,
×
544
            mavlink_address.component_id,
×
545
            channel,
546
            &message,
547
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
548
            _system_impl->get_system_id(),
×
549
            _system_impl->get_autopilot_id(),
×
550
            MAV_FRAME_LOCAL_NED,
551
            IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
552
            position_and_velocity.first.north_m,
×
553
            position_and_velocity.first.east_m,
×
554
            position_and_velocity.first.down_m,
×
555
            position_and_velocity.second.north_m_s,
×
556
            position_and_velocity.second.east_m_s,
×
557
            position_and_velocity.second.down_m_s,
×
558
            0.0f, // afx
559
            0.0f, // afy
560
            0.0f, // afz
561
            to_rad_from_deg(position_and_velocity.first.yaw_deg), // yaw
×
562
            0.0f); // yaw_rate
563
        return message;
×
564
    }) ?
×
565
               Offboard::Result::Success :
566
               Offboard::Result::ConnectionError;
×
567
}
568

569
Offboard::Result OffboardImpl::send_position_velocity_acceleration_ned()
×
570
{
571
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
572

573
    std::lock_guard<std::mutex> lock(_mutex);
×
574
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
575
        mavlink_message_t message;
576
        mavlink_msg_set_position_target_local_ned_pack_chan(
×
577
            mavlink_address.system_id,
×
578
            mavlink_address.component_id,
×
579
            channel,
580
            &message,
581
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
582
            _system_impl->get_system_id(),
×
583
            _system_impl->get_autopilot_id(),
×
584
            MAV_FRAME_LOCAL_NED,
585
            IGNORE_YAW_RATE,
586
            _position_ned_yaw.north_m,
587
            _position_ned_yaw.east_m,
588
            _position_ned_yaw.down_m,
589
            _velocity_ned_yaw.north_m_s,
590
            _velocity_ned_yaw.east_m_s,
591
            _velocity_ned_yaw.down_m_s,
592
            _acceleration_ned.north_m_s2,
593
            _acceleration_ned.east_m_s2,
594
            _acceleration_ned.down_m_s2,
595
            to_rad_from_deg(_position_ned_yaw.yaw_deg), // yaw
596
            0.0f); // yaw_rate
597
        return message;
×
598
    }) ?
×
599
               Offboard::Result::Success :
600
               Offboard::Result::ConnectionError;
×
601
}
×
602

603
Offboard::Result OffboardImpl::send_acceleration_ned()
×
604
{
605
    const static uint16_t IGNORE_X = (1 << 0);
606
    const static uint16_t IGNORE_Y = (1 << 1);
607
    const static uint16_t IGNORE_Z = (1 << 2);
608
    const static uint16_t IGNORE_VX = (1 << 3);
609
    const static uint16_t IGNORE_VY = (1 << 4);
610
    const static uint16_t IGNORE_VZ = (1 << 5);
611
    const static uint16_t IGNORE_YAW = (1 << 10);
612
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
613

614
    const auto acceleration_ned = [this]() {
×
615
        std::lock_guard<std::mutex> lock(_mutex);
×
616
        return _acceleration_ned;
×
617
    }();
×
618

619
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
620
        mavlink_message_t message;
621
        mavlink_msg_set_position_target_local_ned_pack_chan(
×
622
            mavlink_address.system_id,
×
623
            mavlink_address.component_id,
×
624
            channel,
625
            &message,
626
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
627
            _system_impl->get_system_id(),
×
628
            _system_impl->get_autopilot_id(),
×
629
            MAV_FRAME_LOCAL_NED,
630
            IGNORE_X | IGNORE_Y | IGNORE_Z | IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_YAW |
631
                IGNORE_YAW_RATE,
632
            0.0f, // x,
633
            0.0f, // y,
634
            0.0f, // z,
635
            0.0f, // vfx
636
            0.0f, // vfy
637
            0.0f, // vfz
638
            acceleration_ned.north_m_s2,
×
639
            acceleration_ned.east_m_s2,
×
640
            acceleration_ned.down_m_s2,
×
641
            0.0f, // yaw
642
            0.0f); // yaw_rate
643
        return message;
×
644
    }) ?
×
645
               Offboard::Result::Success :
646
               Offboard::Result::ConnectionError;
×
647
}
648

649
Offboard::Result OffboardImpl::send_velocity_body()
×
650
{
651
    const static uint16_t IGNORE_X = (1 << 0);
652
    const static uint16_t IGNORE_Y = (1 << 1);
653
    const static uint16_t IGNORE_Z = (1 << 2);
654
    const static uint16_t IGNORE_AX = (1 << 6);
655
    const static uint16_t IGNORE_AY = (1 << 7);
656
    const static uint16_t IGNORE_AZ = (1 << 8);
657
    const static uint16_t IGNORE_YAW = (1 << 10);
658

659
    const auto velocity_body_yawspeed = [this]() {
×
660
        std::lock_guard<std::mutex> lock(_mutex);
×
661
        return _velocity_body_yawspeed;
×
662
    }();
×
663

664
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
665
        mavlink_message_t message;
666
        mavlink_msg_set_position_target_local_ned_pack_chan(
×
667
            mavlink_address.system_id,
×
668
            mavlink_address.component_id,
×
669
            channel,
670
            &message,
671
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
672
            _system_impl->get_system_id(),
×
673
            _system_impl->get_autopilot_id(),
×
674
            MAV_FRAME_BODY_NED,
675
            IGNORE_X | IGNORE_Y | IGNORE_Z | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW,
676
            0.0f, // x
677
            0.0f, // y
678
            0.0f, // z
679
            velocity_body_yawspeed.forward_m_s,
×
680
            velocity_body_yawspeed.right_m_s,
×
681
            velocity_body_yawspeed.down_m_s,
×
682
            0.0f, // afx
683
            0.0f, // afy
684
            0.0f, // afz
685
            0.0f, // yaw
686
            to_rad_from_deg(velocity_body_yawspeed.yawspeed_deg_s));
×
687
        return message;
×
688
    }) ?
×
689
               Offboard::Result::Success :
690
               Offboard::Result::ConnectionError;
×
691
}
692

693
Offboard::Result OffboardImpl::send_attitude()
×
694
{
695
    const static uint8_t IGNORE_BODY_ROLL_RATE = (1 << 0);
696
    const static uint8_t IGNORE_BODY_PITCH_RATE = (1 << 1);
697
    const static uint8_t IGNORE_BODY_YAW_RATE = (1 << 2);
698

699
    const auto attitude = [this]() {
×
700
        std::lock_guard<std::mutex> lock(_mutex);
×
701
        return _attitude;
×
702
    }();
×
703

704
    const float thrust = _attitude.thrust_value;
×
705
    const float roll = to_rad_from_deg(attitude.roll_deg);
×
706
    const float pitch = to_rad_from_deg(attitude.pitch_deg);
×
707
    const float yaw = to_rad_from_deg(attitude.yaw_deg);
×
708

709
    const double cos_phi_2 = cos(double(roll) / 2.0);
×
710
    const double sin_phi_2 = sin(double(roll) / 2.0);
×
711
    const double cos_theta_2 = cos(double(pitch) / 2.0);
×
712
    const double sin_theta_2 = sin(double(pitch) / 2.0);
×
713
    const double cos_psi_2 = cos(double(yaw) / 2.0);
×
714
    const double sin_psi_2 = sin(double(yaw) / 2.0);
×
715

716
    float q[4];
×
717

718
    q[0] = float(cos_phi_2 * cos_theta_2 * cos_psi_2 + sin_phi_2 * sin_theta_2 * sin_psi_2);
×
719
    q[1] = float(sin_phi_2 * cos_theta_2 * cos_psi_2 - cos_phi_2 * sin_theta_2 * sin_psi_2);
×
720
    q[2] = float(cos_phi_2 * sin_theta_2 * cos_psi_2 + sin_phi_2 * cos_theta_2 * sin_psi_2);
×
721
    q[3] = float(cos_phi_2 * cos_theta_2 * sin_psi_2 - sin_phi_2 * sin_theta_2 * cos_psi_2);
×
722

723
    const float thrust_body[3] = {0.0f, 0.0f, 0.0f};
×
724

725
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
726
        mavlink_message_t message;
727
        mavlink_msg_set_attitude_target_pack_chan(
×
728
            mavlink_address.system_id,
×
729
            mavlink_address.component_id,
×
730
            channel,
731
            &message,
732
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
733
            _system_impl->get_system_id(),
×
734
            _system_impl->get_autopilot_id(),
×
735
            IGNORE_BODY_ROLL_RATE | IGNORE_BODY_PITCH_RATE | IGNORE_BODY_YAW_RATE,
736
            q,
×
737
            0,
738
            0,
739
            0,
740
            thrust,
×
741
            thrust_body);
×
742
        return message;
×
743
    }) ?
×
744
               Offboard::Result::Success :
745
               Offboard::Result::ConnectionError;
×
746
}
747

748
Offboard::Result OffboardImpl::send_attitude_rate()
×
749
{
750
    const static uint8_t IGNORE_ATTITUDE = (1 << 7);
751

752
    const auto attitude_rate = [this]() {
×
753
        std::lock_guard<std::mutex> lock(_mutex);
×
754
        return _attitude_rate;
×
755
    }();
×
756

757
    const float thrust_body[3] = {0.0f, 0.0f, 0.0f};
×
758

759
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
760
        mavlink_message_t message;
761
        mavlink_msg_set_attitude_target_pack_chan(
×
762
            mavlink_address.system_id,
×
763
            mavlink_address.component_id,
×
764
            channel,
765
            &message,
766
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
767
            _system_impl->get_system_id(),
×
768
            _system_impl->get_autopilot_id(),
×
769
            IGNORE_ATTITUDE,
770
            0,
771
            to_rad_from_deg(attitude_rate.roll_deg_s),
×
772
            to_rad_from_deg(attitude_rate.pitch_deg_s),
×
773
            to_rad_from_deg(attitude_rate.yaw_deg_s),
×
774
            _attitude_rate.thrust_value,
775
            thrust_body);
×
776
        return message;
×
777
    }) ?
×
778
               Offboard::Result::Success :
779
               Offboard::Result::ConnectionError;
×
780
}
781

782
Offboard::Result
783
OffboardImpl::send_actuator_control_message(const float* controls, uint8_t group_number)
×
784
{
785
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
786
        mavlink_message_t message;
787
        mavlink_msg_set_actuator_control_target_pack_chan(
×
788
            mavlink_address.system_id,
×
789
            mavlink_address.component_id,
×
790
            channel,
791
            &message,
792
            static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
793
            group_number,
×
794
            _system_impl->get_system_id(),
×
795
            _system_impl->get_autopilot_id(),
×
796
            controls);
×
797
        return message;
×
798
    }) ?
×
799
               Offboard::Result::Success :
800
               Offboard::Result::ConnectionError;
×
801
}
802

803
Offboard::Result OffboardImpl::send_actuator_control()
×
804
{
805
    std::lock_guard<std::mutex> lock(_mutex);
×
806

807
    for (unsigned i = 0; i < 4 && i < _actuator_control.groups.size(); ++i) {
×
808
        _actuator_control.groups[i].controls.resize(8, NAN);
×
809

810
        for (unsigned j = 0; j < 8; ++j) {
×
811
            if (std::isnan(_actuator_control.groups[i].controls[j])) {
×
812
                _actuator_control.groups[i].controls[j] = 0.0f;
×
813
            }
814
        }
815
        auto result = send_actuator_control_message(&_actuator_control.groups[i].controls[0], i);
×
816

817
        if (result != Offboard::Result::Success) {
×
818
            return result;
×
819
        }
820
    }
821

822
    return Offboard::Result::Success;
×
823
}
×
824

825
void OffboardImpl::process_heartbeat(const mavlink_message_t& message)
×
826
{
827
    // Process only Heartbeat coming from the autopilot
828
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
×
829
        return;
×
830
    }
831

832
    mavlink_heartbeat_t heartbeat;
×
833
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
×
834

835
    bool offboard_mode_active = false;
×
836
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
×
837
        FlightMode flight_mode = to_flight_mode_from_custom_mode(
×
838
            _system_impl->autopilot(), _system_impl->get_vehicle_type(), heartbeat.custom_mode);
×
839

840
        if (flight_mode == FlightMode::Offboard) {
×
841
            offboard_mode_active = true;
×
842
        }
843
    }
844

845
    {
846
        // Right after we started offboard we might still be getting heartbeats
847
        // from earlier which don't indicate offboard mode yet.
848
        // Therefore, we make sure we don't stop too eagerly and ignore
849
        // possibly stale heartbeats for some time.
850
        std::lock_guard<std::mutex> lock(_mutex);
×
851
        if (!offboard_mode_active && _mode != Mode::NotActive &&
×
852
            _time.elapsed_since_s(_last_started) > 3.0) {
×
853
            // It seems that we are no longer in offboard mode but still trying to send
854
            // setpoints. Let's stop for now.
855
            stop_sending_setpoints();
×
856
        }
857
    }
×
858
}
859

860
void OffboardImpl::stop_sending_setpoints()
×
861
{
862
    // We assume that we already acquired the mutex in this function.
863

864
    _system_impl->remove_call_every(_call_every_cookie);
×
865
    _mode = Mode::NotActive;
×
866
}
×
867

868
Offboard::Result
869
OffboardImpl::offboard_result_from_command_result(MavlinkCommandSender::Result result)
×
870
{
871
    switch (result) {
×
872
        case MavlinkCommandSender::Result::Success:
×
873
            return Offboard::Result::Success;
×
874
        case MavlinkCommandSender::Result::NoSystem:
×
875
            return Offboard::Result::NoSystem;
×
876
        case MavlinkCommandSender::Result::ConnectionError:
×
877
            return Offboard::Result::ConnectionError;
×
878
        case MavlinkCommandSender::Result::Busy:
×
879
            return Offboard::Result::Busy;
×
880
        case MavlinkCommandSender::Result::Denied:
×
881
            // FALLTHROUGH
882
        case MavlinkCommandSender::Result::TemporarilyRejected:
883
            return Offboard::Result::CommandDenied;
×
884
        case MavlinkCommandSender::Result::Timeout:
×
885
            return Offboard::Result::Timeout;
×
886
        case MavlinkCommandSender::Result::Failed:
×
887
            return Offboard::Result::Failed;
×
888
        default:
×
889
            return Offboard::Result::Unknown;
×
890
    }
891
}
892

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

© 2026 Coveralls, Inc