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

mavlink / MAVSDK / 4309225683

pending completion
4309225683

push

github

GitHub
Merge pull request #1995 from dvinc/offboard-ardupilot-rover

7 of 7 new or added lines in 3 files covered. (100.0%)

7418 of 24192 relevant lines covered (30.66%)

21.61 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 "mavsdk_math.h"
4
#include "offboard_impl.h"
5
#include "mavsdk_impl.h"
6
#include "px4_custom_mode.h"
7

8
namespace mavsdk {
9

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

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

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

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

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

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

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

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

56
    return offboard_result_from_command_result(_parent->set_flight_mode(FlightMode::Offboard));
×
57
}
58

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

68
    return offboard_result_from_command_result(_parent->set_flight_mode(FlightMode::Hold));
×
69
}
70

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

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

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

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

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

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

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

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

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

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

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

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

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

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

174
    // also send it right now to reduce latency
175
    return send_position_global();
×
176
}
177

178
Offboard::Result OffboardImpl::set_velocity_ned(Offboard::VelocityNedYaw velocity_ned_yaw)
×
179
{
180
    {
181
        std::lock_guard<std::mutex> lock(_mutex);
×
182
        _velocity_ned_yaw = velocity_ned_yaw;
×
183

184
        if (_mode != Mode::VelocityNed) {
×
185
            if (_call_every_cookie) {
×
186
                // If we're already sending other setpoints, stop that now.
187
                _parent->remove_call_every(_call_every_cookie);
×
188
                _call_every_cookie = nullptr;
×
189
            }
190
            // We automatically send Ned setpoints from now on.
191
            _parent->add_call_every(
×
192
                [this]() { send_velocity_ned(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
193

194
            _mode = Mode::VelocityNed;
×
195
        } else {
196
            // We're already sending these kind of setpoints. Since the setpoint change, let's
197
            // reschedule the next call, so we don't send setpoints too often.
198
            _parent->reset_call_every(_call_every_cookie);
×
199
        }
200
    }
201
    // also send it right now to reduce latency
202
    return send_velocity_ned();
×
203
}
204

205
Offboard::Result OffboardImpl::set_position_velocity_ned(
×
206
    Offboard::PositionNedYaw position_ned_yaw, Offboard::VelocityNedYaw velocity_ned_yaw)
207
{
208
    {
209
        std::lock_guard<std::mutex> lock(_mutex);
×
210
        _position_ned_yaw = position_ned_yaw;
×
211
        _velocity_ned_yaw = velocity_ned_yaw;
×
212

213
        if (_mode != Mode::PositionVelocityNed) {
×
214
            if (_call_every_cookie) {
×
215
                // If we're already sending other setpoints, stop that now.
216
                _parent->remove_call_every(_call_every_cookie);
×
217
                _call_every_cookie = nullptr;
×
218
            }
219
            // We automatically send Ned setpoints from now on.
220
            _parent->add_call_every(
×
221
                [this]() { send_position_velocity_ned(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
222

223
            _mode = Mode::PositionVelocityNed;
×
224
        } else {
225
            // We're already sending these kind of setpoints. Since the setpoint change, let's
226
            // reschedule the next call, so we don't send setpoints too often.
227
            _parent->reset_call_every(_call_every_cookie);
×
228
        }
229
    }
230

231
    // also send it right now to reduce latency
232
    return send_position_velocity_ned();
×
233
}
234

235
Offboard::Result OffboardImpl::set_acceleration_ned(Offboard::AccelerationNed acceleration_ned)
×
236
{
237
    {
238
        std::lock_guard<std::mutex> lock(_mutex);
×
239
        _acceleration_ned = acceleration_ned;
×
240

241
        if (_mode != Mode::AccelerationNed) {
×
242
            if (_call_every_cookie) {
×
243
                // If we're already sending other setpoints, stop that now.
244
                _parent->remove_call_every(_call_every_cookie);
×
245
                _call_every_cookie = nullptr;
×
246
            }
247
            // We automatically send Ned setpoints from now on.
248
            _parent->add_call_every(
×
249
                [this]() { send_acceleration_ned(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
250

251
            _mode = Mode::AccelerationNed;
×
252
        } else {
253
            // We're already sending these kind of setpoints. Since the setpoint change, let's
254
            // reschedule the next call, so we don't send setpoints too often.
255
            _parent->reset_call_every(_call_every_cookie);
×
256
        }
257
    }
258

259
    // also send it right now to reduce latency
260
    return send_acceleration_ned();
×
261
}
262

263
Offboard::Result
264
OffboardImpl::set_velocity_body(Offboard::VelocityBodyYawspeed velocity_body_yawspeed)
×
265
{
266
    {
267
        std::lock_guard<std::mutex> lock(_mutex);
×
268
        _velocity_body_yawspeed = velocity_body_yawspeed;
×
269

270
        if (_mode != Mode::VelocityBody) {
×
271
            if (_call_every_cookie) {
×
272
                // If we're already sending other setpoints, stop that now.
273
                _parent->remove_call_every(_call_every_cookie);
×
274
                _call_every_cookie = nullptr;
×
275
            }
276
            // We automatically send body setpoints from now on.
277
            _parent->add_call_every(
×
278
                [this]() { send_velocity_body(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
279

280
            _mode = Mode::VelocityBody;
×
281
        } else {
282
            // We're already sending these kind of setpoints. Since the setpoint change, let's
283
            // reschedule the next call, so we don't send setpoints too often.
284
            _parent->reset_call_every(_call_every_cookie);
×
285
        }
286
    }
287

288
    // also send it right now to reduce latency
289
    return send_velocity_body();
×
290
}
291

292
Offboard::Result OffboardImpl::set_attitude(Offboard::Attitude attitude)
×
293
{
294
    {
295
        std::lock_guard<std::mutex> lock(_mutex);
×
296
        _attitude = attitude;
×
297

298
        if (_mode != Mode::Attitude) {
×
299
            if (_call_every_cookie) {
×
300
                // If we're already sending other setpoints, stop that now.
301
                _parent->remove_call_every(_call_every_cookie);
×
302
                _call_every_cookie = nullptr;
×
303
            }
304
            // We automatically send body setpoints from now on.
305
            _parent->add_call_every(
×
306
                [this]() { send_attitude(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
307

308
            _mode = Mode::Attitude;
×
309
        } else {
310
            // We're already sending these kind of setpoints. Since the setpoint change, let's
311
            // reschedule the next call, so we don't send setpoints too often.
312
            _parent->reset_call_every(_call_every_cookie);
×
313
        }
314
    }
315

316
    // also send it right now to reduce latency
317
    return send_attitude();
×
318
}
319

320
Offboard::Result OffboardImpl::set_attitude_rate(Offboard::AttitudeRate attitude_rate)
×
321
{
322
    {
323
        std::lock_guard<std::mutex> lock(_mutex);
×
324
        _attitude_rate = attitude_rate;
×
325

326
        if (_mode != Mode::AttitudeRate) {
×
327
            if (_call_every_cookie) {
×
328
                // If we're already sending other setpoints, stop that now.
329
                _parent->remove_call_every(_call_every_cookie);
×
330
                _call_every_cookie = nullptr;
×
331
            }
332
            // We automatically send body setpoints from now on.
333
            _parent->add_call_every(
×
334
                [this]() { send_attitude_rate(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
335

336
            _mode = Mode::AttitudeRate;
×
337
        } else {
338
            // We're already sending these kind of setpoints. Since the setpoint change, let's
339
            // reschedule the next call, so we don't send setpoints too often.
340
            _parent->reset_call_every(_call_every_cookie);
×
341
        }
342
    }
343

344
    // also send it right now to reduce latency
345
    return send_attitude_rate();
×
346
}
347

348
Offboard::Result OffboardImpl::set_actuator_control(Offboard::ActuatorControl actuator_control)
×
349
{
350
    {
351
        std::lock_guard<std::mutex> lock(_mutex);
×
352
        _actuator_control = actuator_control;
×
353

354
        if (_mode != Mode::ActuatorControl) {
×
355
            if (_call_every_cookie) {
×
356
                // If we're already sending other setpoints, stop that now.
357
                _parent->remove_call_every(_call_every_cookie);
×
358
                _call_every_cookie = nullptr;
×
359
            }
360
            // We automatically send motor rate values from now on.
361
            _parent->add_call_every(
×
362
                [this]() { send_actuator_control(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
363

364
            _mode = Mode::ActuatorControl;
×
365
        } else {
366
            // We're already sending these kind of values. Since the value changes, let's
367
            // reschedule the next call, so we don't send values too often.
368
            _parent->reset_call_every(_call_every_cookie);
×
369
        }
370
    }
371

372
    // It gets sent immediately as part of add_call_every.
373
    return Offboard::Result::Success;
×
374
}
375

376
Offboard::Result OffboardImpl::send_position_ned()
×
377
{
378
    const static uint16_t IGNORE_VX = (1 << 3);
379
    const static uint16_t IGNORE_VY = (1 << 4);
380
    const static uint16_t IGNORE_VZ = (1 << 5);
381
    const static uint16_t IGNORE_AX = (1 << 6);
382
    const static uint16_t IGNORE_AY = (1 << 7);
383
    const static uint16_t IGNORE_AZ = (1 << 8);
384
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
385

386
    const auto position_ned_yaw = [this]() {
×
387
        std::lock_guard<std::mutex> lock(_mutex);
×
388
        return _position_ned_yaw;
×
389
    }();
×
390

391
    mavlink_message_t message;
×
392
    mavlink_msg_set_position_target_local_ned_pack(
×
393
        _parent->get_own_system_id(),
×
394
        _parent->get_own_component_id(),
×
395
        &message,
396
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
397
        _parent->get_system_id(),
×
398
        _parent->get_autopilot_id(),
×
399
        MAV_FRAME_LOCAL_NED,
400
        IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
401
        position_ned_yaw.north_m,
×
402
        position_ned_yaw.east_m,
×
403
        position_ned_yaw.down_m,
×
404
        0.0f, // vx
405
        0.0f, // vy
406
        0.0f, // vz
407
        0.0f, // afx
408
        0.0f, // afy
409
        0.0f, // afz
410
        to_rad_from_deg(position_ned_yaw.yaw_deg), // yaw
×
411
        0.0f); // yaw_rate
412
    return _parent->send_message(message) ? Offboard::Result::Success :
×
413
                                            Offboard::Result::ConnectionError;
×
414
}
415

416
Offboard::Result OffboardImpl::send_position_global()
×
417
{
418
    const static uint16_t IGNORE_VX = (1 << 3);
419
    const static uint16_t IGNORE_VY = (1 << 4);
420
    const static uint16_t IGNORE_VZ = (1 << 5);
421
    const static uint16_t IGNORE_AX = (1 << 6);
422
    const static uint16_t IGNORE_AY = (1 << 7);
423
    const static uint16_t IGNORE_AZ = (1 << 8);
424
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
425

426
    const auto position_global_yaw = [this]() {
×
427
        std::lock_guard<std::mutex> lock(_mutex);
×
428
        return _position_global_yaw;
×
429
    }();
×
430

431
    MAV_FRAME frame;
432
    switch (position_global_yaw.altitude_type) {
×
433
        case Offboard::PositionGlobalYaw::AltitudeType::Amsl:
×
434
            frame = MAV_FRAME_GLOBAL_INT;
×
435
            break;
×
436
        case Offboard::PositionGlobalYaw::AltitudeType::Agl:
×
437
            frame = MAV_FRAME_GLOBAL_TERRAIN_ALT_INT;
×
438
            break;
×
439
        case Offboard::PositionGlobalYaw::AltitudeType::RelHome:
×
440
            frame = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT;
×
441
            break;
×
442
        default:
×
443
            return Offboard::Result::CommandDenied;
×
444
            break;
445
    }
446

447
    mavlink_message_t message;
×
448
    mavlink_msg_set_position_target_global_int_pack(
×
449
        _parent->get_own_system_id(),
×
450
        _parent->get_own_component_id(),
×
451
        &message,
452
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
453
        _parent->get_system_id(),
×
454
        _parent->get_autopilot_id(),
×
455
        frame,
456
        IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
457
        (int32_t)(position_global_yaw.lat_deg * 1.0e7),
×
458
        (int32_t)(position_global_yaw.lon_deg * 1.0e7),
×
459
        position_global_yaw.alt_m,
×
460
        0.0f, // vx
461
        0.0f, // vy
462
        0.0f, // vz
463
        0.0f, // afx
464
        0.0f, // afy
465
        0.0f, // afz
466
        to_rad_from_deg(position_global_yaw.yaw_deg), // yaw
×
467
        0.0f); // yaw_rate
468
    return _parent->send_message(message) ? Offboard::Result::Success :
×
469
                                            Offboard::Result::ConnectionError;
×
470
}
471

472
Offboard::Result OffboardImpl::send_velocity_ned()
×
473
{
474
    const static uint16_t IGNORE_X = (1 << 0);
475
    const static uint16_t IGNORE_Y = (1 << 1);
476
    const static uint16_t IGNORE_Z = (1 << 2);
477
    const static uint16_t IGNORE_AX = (1 << 6);
478
    const static uint16_t IGNORE_AY = (1 << 7);
479
    const static uint16_t IGNORE_AZ = (1 << 8);
480
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
481

482
    const auto velocity_ned_yaw = [this]() {
×
483
        std::lock_guard<std::mutex> lock(_mutex);
×
484
        return _velocity_ned_yaw;
×
485
    }();
×
486

487
    mavlink_message_t message;
×
488
    mavlink_msg_set_position_target_local_ned_pack(
×
489
        _parent->get_own_system_id(),
×
490
        _parent->get_own_component_id(),
×
491
        &message,
492
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
493
        _parent->get_system_id(),
×
494
        _parent->get_autopilot_id(),
×
495
        MAV_FRAME_LOCAL_NED,
496
        IGNORE_X | IGNORE_Y | IGNORE_Z | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
497
        0.0f, // x,
498
        0.0f, // y,
499
        0.0f, // z,
500
        velocity_ned_yaw.north_m_s,
×
501
        velocity_ned_yaw.east_m_s,
×
502
        velocity_ned_yaw.down_m_s,
×
503
        0.0f, // afx
504
        0.0f, // afy
505
        0.0f, // afz
506
        to_rad_from_deg(velocity_ned_yaw.yaw_deg), // yaw
×
507
        0.0f); // yaw_rate
508
    return _parent->send_message(message) ? Offboard::Result::Success :
×
509
                                            Offboard::Result::ConnectionError;
×
510
}
511

512
Offboard::Result OffboardImpl::send_position_velocity_ned()
×
513
{
514
    const static uint16_t IGNORE_AX = (1 << 6);
515
    const static uint16_t IGNORE_AY = (1 << 7);
516
    const static uint16_t IGNORE_AZ = (1 << 8);
517
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
518

519
    const auto position_and_velocity = [this]() {
×
520
        std::lock_guard<std::mutex> lock(_mutex);
×
521
        return std::make_pair<>(_position_ned_yaw, _velocity_ned_yaw);
×
522
    }();
×
523

524
    mavlink_message_t message;
×
525
    mavlink_msg_set_position_target_local_ned_pack(
×
526
        _parent->get_own_system_id(),
×
527
        _parent->get_own_component_id(),
×
528
        &message,
529
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
530
        _parent->get_system_id(),
×
531
        _parent->get_autopilot_id(),
×
532
        MAV_FRAME_LOCAL_NED,
533
        IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
534
        position_and_velocity.first.north_m,
×
535
        position_and_velocity.first.east_m,
×
536
        position_and_velocity.first.down_m,
×
537
        position_and_velocity.second.north_m_s,
×
538
        position_and_velocity.second.east_m_s,
×
539
        position_and_velocity.second.down_m_s,
×
540
        0.0f, // afx
541
        0.0f, // afy
542
        0.0f, // afz
543
        to_rad_from_deg(position_and_velocity.first.yaw_deg), // yaw
×
544
        0.0f); // yaw_rate
545
    return _parent->send_message(message) ? Offboard::Result::Success :
×
546
                                            Offboard::Result::ConnectionError;
×
547
}
548

549
Offboard::Result OffboardImpl::send_acceleration_ned()
×
550
{
551
    const static uint16_t IGNORE_X = (1 << 0);
552
    const static uint16_t IGNORE_Y = (1 << 1);
553
    const static uint16_t IGNORE_Z = (1 << 2);
554
    const static uint16_t IGNORE_VX = (1 << 3);
555
    const static uint16_t IGNORE_VY = (1 << 4);
556
    const static uint16_t IGNORE_VZ = (1 << 5);
557
    const static uint16_t IGNORE_YAW = (1 << 10);
558
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
559

560
    const auto acceleration_ned = [this]() {
×
561
        std::lock_guard<std::mutex> lock(_mutex);
×
562
        return _acceleration_ned;
×
563
    }();
×
564

565
    mavlink_message_t message;
×
566
    mavlink_msg_set_position_target_local_ned_pack(
×
567
        _parent->get_own_system_id(),
×
568
        _parent->get_own_component_id(),
×
569
        &message,
570
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
571
        _parent->get_system_id(),
×
572
        _parent->get_autopilot_id(),
×
573
        MAV_FRAME_LOCAL_NED,
574
        IGNORE_X | IGNORE_Y | IGNORE_Z | IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_YAW |
575
            IGNORE_YAW_RATE,
576
        0.0f, // x,
577
        0.0f, // y,
578
        0.0f, // z,
579
        0.0f, // vfx
580
        0.0f, // vfy
581
        0.0f, // vfz
582
        acceleration_ned.north_m_s2,
×
583
        acceleration_ned.east_m_s2,
×
584
        acceleration_ned.down_m_s2,
×
585
        0.0f, // yaw
586
        0.0f); // yaw_rate
587
    return _parent->send_message(message) ? Offboard::Result::Success :
×
588
                                            Offboard::Result::ConnectionError;
×
589
}
590

591
Offboard::Result OffboardImpl::send_velocity_body()
×
592
{
593
    const static uint16_t IGNORE_X = (1 << 0);
594
    const static uint16_t IGNORE_Y = (1 << 1);
595
    const static uint16_t IGNORE_Z = (1 << 2);
596
    const static uint16_t IGNORE_AX = (1 << 6);
597
    const static uint16_t IGNORE_AY = (1 << 7);
598
    const static uint16_t IGNORE_AZ = (1 << 8);
599
    const static uint16_t IGNORE_YAW = (1 << 10);
600

601
    const auto velocity_body_yawspeed = [this]() {
×
602
        std::lock_guard<std::mutex> lock(_mutex);
×
603
        return _velocity_body_yawspeed;
×
604
    }();
×
605

606
    mavlink_message_t message;
×
607
    mavlink_msg_set_position_target_local_ned_pack(
×
608
        _parent->get_own_system_id(),
×
609
        _parent->get_own_component_id(),
×
610
        &message,
611
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
612
        _parent->get_system_id(),
×
613
        _parent->get_autopilot_id(),
×
614
        MAV_FRAME_BODY_NED,
615
        IGNORE_X | IGNORE_Y | IGNORE_Z | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW,
616
        0.0f, // x
617
        0.0f, // y
618
        0.0f, // z
619
        velocity_body_yawspeed.forward_m_s,
×
620
        velocity_body_yawspeed.right_m_s,
×
621
        velocity_body_yawspeed.down_m_s,
×
622
        0.0f, // afx
623
        0.0f, // afy
624
        0.0f, // afz
625
        0.0f, // yaw
626
        to_rad_from_deg(velocity_body_yawspeed.yawspeed_deg_s));
×
627
    return _parent->send_message(message) ? Offboard::Result::Success :
×
628
                                            Offboard::Result::ConnectionError;
×
629
}
630

631
Offboard::Result OffboardImpl::send_attitude()
×
632
{
633
    const static uint8_t IGNORE_BODY_ROLL_RATE = (1 << 0);
634
    const static uint8_t IGNORE_BODY_PITCH_RATE = (1 << 1);
635
    const static uint8_t IGNORE_BODY_YAW_RATE = (1 << 2);
636

637
    const auto attitude = [this]() {
×
638
        std::lock_guard<std::mutex> lock(_mutex);
×
639
        return _attitude;
×
640
    }();
×
641

642
    const float thrust = _attitude.thrust_value;
×
643
    const float roll = to_rad_from_deg(attitude.roll_deg);
×
644
    const float pitch = to_rad_from_deg(attitude.pitch_deg);
×
645
    const float yaw = to_rad_from_deg(attitude.yaw_deg);
×
646

647
    const double cos_phi_2 = cos(double(roll) / 2.0);
×
648
    const double sin_phi_2 = sin(double(roll) / 2.0);
×
649
    const double cos_theta_2 = cos(double(pitch) / 2.0);
×
650
    const double sin_theta_2 = sin(double(pitch) / 2.0);
×
651
    const double cos_psi_2 = cos(double(yaw) / 2.0);
×
652
    const double sin_psi_2 = sin(double(yaw) / 2.0);
×
653

654
    float q[4];
×
655

656
    q[0] = float(cos_phi_2 * cos_theta_2 * cos_psi_2 + sin_phi_2 * sin_theta_2 * sin_psi_2);
×
657
    q[1] = float(sin_phi_2 * cos_theta_2 * cos_psi_2 - cos_phi_2 * sin_theta_2 * sin_psi_2);
×
658
    q[2] = float(cos_phi_2 * sin_theta_2 * cos_psi_2 + sin_phi_2 * cos_theta_2 * sin_psi_2);
×
659
    q[3] = float(cos_phi_2 * cos_theta_2 * sin_psi_2 - sin_phi_2 * sin_theta_2 * cos_psi_2);
×
660

661
    const float thrust_body[3] = {0.0f, 0.0f, 0.0f};
×
662

663
    mavlink_message_t message;
×
664
    mavlink_msg_set_attitude_target_pack(
×
665
        _parent->get_own_system_id(),
×
666
        _parent->get_own_component_id(),
×
667
        &message,
668
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
669
        _parent->get_system_id(),
×
670
        _parent->get_autopilot_id(),
×
671
        IGNORE_BODY_ROLL_RATE | IGNORE_BODY_PITCH_RATE | IGNORE_BODY_YAW_RATE,
672
        q,
673
        0,
674
        0,
675
        0,
676
        thrust,
677
        thrust_body);
678
    return _parent->send_message(message) ? Offboard::Result::Success :
×
679
                                            Offboard::Result::ConnectionError;
×
680
}
681

682
Offboard::Result OffboardImpl::send_attitude_rate()
×
683
{
684
    const static uint8_t IGNORE_ATTITUDE = (1 << 7);
685

686
    const auto attitude_rate = [this]() {
×
687
        std::lock_guard<std::mutex> lock(_mutex);
×
688
        return _attitude_rate;
×
689
    }();
×
690

691
    const float thrust_body[3] = {0.0f, 0.0f, 0.0f};
×
692

693
    mavlink_message_t message;
×
694
    mavlink_msg_set_attitude_target_pack(
×
695
        _parent->get_own_system_id(),
×
696
        _parent->get_own_component_id(),
×
697
        &message,
698
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
699
        _parent->get_system_id(),
×
700
        _parent->get_autopilot_id(),
×
701
        IGNORE_ATTITUDE,
702
        0,
703
        to_rad_from_deg(attitude_rate.roll_deg_s),
×
704
        to_rad_from_deg(attitude_rate.pitch_deg_s),
×
705
        to_rad_from_deg(attitude_rate.yaw_deg_s),
×
706
        _attitude_rate.thrust_value,
707
        thrust_body);
708
    return _parent->send_message(message) ? Offboard::Result::Success :
×
709
                                            Offboard::Result::ConnectionError;
×
710
}
711

712
Offboard::Result
713
OffboardImpl::send_actuator_control_message(const float* controls, uint8_t group_number)
×
714
{
715
    mavlink_message_t message;
×
716
    mavlink_msg_set_actuator_control_target_pack(
×
717
        _parent->get_own_system_id(),
×
718
        _parent->get_own_component_id(),
×
719
        &message,
720
        static_cast<uint32_t>(_parent->get_time().elapsed_ms()),
×
721
        group_number,
722
        _parent->get_system_id(),
×
723
        _parent->get_autopilot_id(),
×
724
        controls);
725
    return _parent->send_message(message) ? Offboard::Result::Success :
×
726
                                            Offboard::Result::ConnectionError;
×
727
}
728

729
Offboard::Result OffboardImpl::send_actuator_control()
×
730
{
731
    std::lock_guard<std::mutex> lock(_mutex);
×
732

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

736
        for (unsigned j = 0; j < 8; ++j) {
×
737
            if (std::isnan(_actuator_control.groups[i].controls[j])) {
×
738
                _actuator_control.groups[i].controls[j] = 0.0f;
×
739
            }
740
        }
741
        auto result = send_actuator_control_message(&_actuator_control.groups[i].controls[0], i);
×
742

743
        if (result != Offboard::Result::Success) {
×
744
            return result;
×
745
        }
746
    }
747

748
    return Offboard::Result::Success;
×
749
}
750

751
void OffboardImpl::process_heartbeat(const mavlink_message_t& message)
×
752
{
753
    // Process only Heartbeat coming from the autopilot
754
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
×
755
        return;
×
756
    }
757

758
    mavlink_heartbeat_t heartbeat;
×
759
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
×
760

761
    bool offboard_mode_active = false;
×
762
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
×
763
        FlightMode flight_mode = to_flight_mode_from_custom_mode(
×
764
            _parent->autopilot(), _parent->get_vehicle_type(), heartbeat.custom_mode);
×
765

766
        if (flight_mode == FlightMode::Offboard) {
×
767
            offboard_mode_active = true;
×
768
        }
769
    }
770

771
    {
772
        // Right after we started offboard we might still be getting heartbeats
773
        // from earlier which don't indicate offboard mode yet.
774
        // Therefore, we make sure we don't stop too eagerly and ignore
775
        // possibly stale heartbeats for some time.
776
        std::lock_guard<std::mutex> lock(_mutex);
×
777
        if (!offboard_mode_active && _mode != Mode::NotActive &&
×
778
            _time.elapsed_since_s(_last_started) > 3.0) {
×
779
            // It seems that we are no longer in offboard mode but still trying to send
780
            // setpoints. Let's stop for now.
781
            stop_sending_setpoints();
×
782
        }
783
    }
784
}
785

786
void OffboardImpl::stop_sending_setpoints()
×
787
{
788
    // We assume that we already acquired the mutex in this function.
789

790
    if (_call_every_cookie != nullptr) {
×
791
        _parent->remove_call_every(_call_every_cookie);
×
792
        _call_every_cookie = nullptr;
×
793
    }
794
    _mode = Mode::NotActive;
×
795
}
×
796

797
Offboard::Result
798
OffboardImpl::offboard_result_from_command_result(MavlinkCommandSender::Result result)
×
799
{
800
    switch (result) {
×
801
        case MavlinkCommandSender::Result::Success:
×
802
            return Offboard::Result::Success;
×
803
        case MavlinkCommandSender::Result::NoSystem:
×
804
            return Offboard::Result::NoSystem;
×
805
        case MavlinkCommandSender::Result::ConnectionError:
×
806
            return Offboard::Result::ConnectionError;
×
807
        case MavlinkCommandSender::Result::Busy:
×
808
            return Offboard::Result::Busy;
×
809
        case MavlinkCommandSender::Result::Denied:
×
810
            // FALLTHROUGH
811
        case MavlinkCommandSender::Result::TemporarilyRejected:
812
            return Offboard::Result::CommandDenied;
×
813
        case MavlinkCommandSender::Result::Timeout:
×
814
            return Offboard::Result::Timeout;
×
815
        case MavlinkCommandSender::Result::Failed:
×
816
            return Offboard::Result::Failed;
×
817
        default:
×
818
            return Offboard::Result::Unknown;
×
819
    }
820
}
821

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