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

mavlink / MAVSDK / 5108905537

pending completion
5108905537

push

github

web-flow
Merge pull request #2057 from alireza787b/offboard-pos-vel-acc

added set_position_velocity_acceleration_ned offboard function

29 of 29 new or added lines in 2 files covered. (100.0%)

7716 of 24871 relevant lines covered (31.02%)

19.92 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
    _system_impl->register_plugin(this);
×
13
}
×
14

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

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

25
void OffboardImpl::init()
×
26
{
27
    _system_impl->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
    _system_impl->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(_system_impl->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(_system_impl->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
                _system_impl->call_user_callback(
×
79
                    [callback]() { callback(Offboard::Result::NoSetpointSet); });
80
            }
81
            return;
×
82
        }
83
        _last_started = _time.steady_time();
×
84
    }
85

86
    _system_impl->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
    _system_impl->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
        _system_impl->call_user_callback(
×
119
            [callback, offboard_result]() { callback(offboard_result); });
120
    }
121
}
×
122

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

236
Offboard::Result OffboardImpl::set_position_velocity_acceleration_ned(
×
237
    Offboard::PositionNedYaw position_ned_yaw,
238
    Offboard::VelocityNedYaw velocity_ned_yaw,
239
    Offboard::AccelerationNed acceleration_ned)
240
{
241
    {
242
        std::lock_guard<std::mutex> lock(_mutex);
×
243
        _position_ned_yaw = position_ned_yaw;
×
244
        _velocity_ned_yaw = velocity_ned_yaw;
×
245
        _acceleration_ned = acceleration_ned;
×
246

247
        if (_mode != Mode::PositionVelocityAccelerationNed) {
×
248
            if (_call_every_cookie) {
×
249
                // If we're already sending other setpoints, stop that now.
250
                _system_impl->remove_call_every(_call_every_cookie);
×
251
                _call_every_cookie = nullptr;
×
252
            }
253
            // We automatically send Ned setpoints from now on.
254
            _system_impl->add_call_every(
×
255
                [this]() { send_position_velocity_acceleration_ned(); },
×
256
                SEND_INTERVAL_S,
×
257
                &_call_every_cookie);
258

259
            _mode = Mode::PositionVelocityAccelerationNed;
×
260
        } else {
261
            // We're already sending these kind of setpoints. Since the setpoint change, let's
262
            // reschedule the next call, so we don't send setpoints too often.
263
            _system_impl->reset_call_every(_call_every_cookie);
×
264
        }
265
    }
266

267
    // also send it right now to reduce latency
268
    return send_position_velocity_acceleration_ned();
×
269
}
270

271
Offboard::Result OffboardImpl::set_acceleration_ned(Offboard::AccelerationNed acceleration_ned)
×
272
{
273
    {
274
        std::lock_guard<std::mutex> lock(_mutex);
×
275
        _acceleration_ned = acceleration_ned;
×
276

277
        if (_mode != Mode::AccelerationNed) {
×
278
            if (_call_every_cookie) {
×
279
                // If we're already sending other setpoints, stop that now.
280
                _system_impl->remove_call_every(_call_every_cookie);
×
281
                _call_every_cookie = nullptr;
×
282
            }
283
            // We automatically send Ned setpoints from now on.
284
            _system_impl->add_call_every(
×
285
                [this]() { send_acceleration_ned(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
286

287
            _mode = Mode::AccelerationNed;
×
288
        } else {
289
            // We're already sending these kind of setpoints. Since the setpoint change, let's
290
            // reschedule the next call, so we don't send setpoints too often.
291
            _system_impl->reset_call_every(_call_every_cookie);
×
292
        }
293
    }
294

295
    // also send it right now to reduce latency
296
    return send_acceleration_ned();
×
297
}
298

299
Offboard::Result
300
OffboardImpl::set_velocity_body(Offboard::VelocityBodyYawspeed velocity_body_yawspeed)
×
301
{
302
    {
303
        std::lock_guard<std::mutex> lock(_mutex);
×
304
        _velocity_body_yawspeed = velocity_body_yawspeed;
×
305

306
        if (_mode != Mode::VelocityBody) {
×
307
            if (_call_every_cookie) {
×
308
                // If we're already sending other setpoints, stop that now.
309
                _system_impl->remove_call_every(_call_every_cookie);
×
310
                _call_every_cookie = nullptr;
×
311
            }
312
            // We automatically send body setpoints from now on.
313
            _system_impl->add_call_every(
×
314
                [this]() { send_velocity_body(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
315

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

324
    // also send it right now to reduce latency
325
    return send_velocity_body();
×
326
}
327

328
Offboard::Result OffboardImpl::set_attitude(Offboard::Attitude attitude)
×
329
{
330
    {
331
        std::lock_guard<std::mutex> lock(_mutex);
×
332
        _attitude = attitude;
×
333

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

344
            _mode = Mode::Attitude;
×
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();
×
354
}
355

356
Offboard::Result OffboardImpl::set_attitude_rate(Offboard::AttitudeRate attitude_rate)
×
357
{
358
    {
359
        std::lock_guard<std::mutex> lock(_mutex);
×
360
        _attitude_rate = attitude_rate;
×
361

362
        if (_mode != Mode::AttitudeRate) {
×
363
            if (_call_every_cookie) {
×
364
                // If we're already sending other setpoints, stop that now.
365
                _system_impl->remove_call_every(_call_every_cookie);
×
366
                _call_every_cookie = nullptr;
×
367
            }
368
            // We automatically send body setpoints from now on.
369
            _system_impl->add_call_every(
×
370
                [this]() { send_attitude_rate(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
371

372
            _mode = Mode::AttitudeRate;
×
373
        } else {
374
            // We're already sending these kind of setpoints. Since the setpoint change, let's
375
            // reschedule the next call, so we don't send setpoints too often.
376
            _system_impl->reset_call_every(_call_every_cookie);
×
377
        }
378
    }
379

380
    // also send it right now to reduce latency
381
    return send_attitude_rate();
×
382
}
383

384
Offboard::Result OffboardImpl::set_actuator_control(Offboard::ActuatorControl actuator_control)
×
385
{
386
    {
387
        std::lock_guard<std::mutex> lock(_mutex);
×
388
        _actuator_control = actuator_control;
×
389

390
        if (_mode != Mode::ActuatorControl) {
×
391
            if (_call_every_cookie) {
×
392
                // If we're already sending other setpoints, stop that now.
393
                _system_impl->remove_call_every(_call_every_cookie);
×
394
                _call_every_cookie = nullptr;
×
395
            }
396
            // We automatically send motor rate values from now on.
397
            _system_impl->add_call_every(
×
398
                [this]() { send_actuator_control(); }, SEND_INTERVAL_S, &_call_every_cookie);
×
399

400
            _mode = Mode::ActuatorControl;
×
401
        } else {
402
            // We're already sending these kind of values. Since the value changes, let's
403
            // reschedule the next call, so we don't send values too often.
404
            _system_impl->reset_call_every(_call_every_cookie);
×
405
        }
406
    }
407

408
    // It gets sent immediately as part of add_call_every.
409
    return Offboard::Result::Success;
×
410
}
411

412
Offboard::Result OffboardImpl::send_position_ned()
×
413
{
414
    const static uint16_t IGNORE_VX = (1 << 3);
415
    const static uint16_t IGNORE_VY = (1 << 4);
416
    const static uint16_t IGNORE_VZ = (1 << 5);
417
    const static uint16_t IGNORE_AX = (1 << 6);
418
    const static uint16_t IGNORE_AY = (1 << 7);
419
    const static uint16_t IGNORE_AZ = (1 << 8);
420
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
421

422
    const auto position_ned_yaw = [this]() {
×
423
        std::lock_guard<std::mutex> lock(_mutex);
×
424
        return _position_ned_yaw;
×
425
    }();
×
426

427
    mavlink_message_t message;
×
428
    mavlink_msg_set_position_target_local_ned_pack(
×
429
        _system_impl->get_own_system_id(),
×
430
        _system_impl->get_own_component_id(),
×
431
        &message,
432
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
433
        _system_impl->get_system_id(),
×
434
        _system_impl->get_autopilot_id(),
×
435
        MAV_FRAME_LOCAL_NED,
436
        IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
437
        position_ned_yaw.north_m,
×
438
        position_ned_yaw.east_m,
×
439
        position_ned_yaw.down_m,
×
440
        0.0f, // vx
441
        0.0f, // vy
442
        0.0f, // vz
443
        0.0f, // afx
444
        0.0f, // afy
445
        0.0f, // afz
446
        to_rad_from_deg(position_ned_yaw.yaw_deg), // yaw
×
447
        0.0f); // yaw_rate
448
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
449
                                                 Offboard::Result::ConnectionError;
×
450
}
451

452
Offboard::Result OffboardImpl::send_position_global()
×
453
{
454
    const static uint16_t IGNORE_VX = (1 << 3);
455
    const static uint16_t IGNORE_VY = (1 << 4);
456
    const static uint16_t IGNORE_VZ = (1 << 5);
457
    const static uint16_t IGNORE_AX = (1 << 6);
458
    const static uint16_t IGNORE_AY = (1 << 7);
459
    const static uint16_t IGNORE_AZ = (1 << 8);
460
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
461

462
    const auto position_global_yaw = [this]() {
×
463
        std::lock_guard<std::mutex> lock(_mutex);
×
464
        return _position_global_yaw;
×
465
    }();
×
466

467
    MAV_FRAME frame;
468
    switch (position_global_yaw.altitude_type) {
×
469
        case Offboard::PositionGlobalYaw::AltitudeType::Amsl:
×
470
            frame = MAV_FRAME_GLOBAL_INT;
×
471
            break;
×
472
        case Offboard::PositionGlobalYaw::AltitudeType::Agl:
×
473
            frame = MAV_FRAME_GLOBAL_TERRAIN_ALT_INT;
×
474
            break;
×
475
        case Offboard::PositionGlobalYaw::AltitudeType::RelHome:
×
476
            frame = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT;
×
477
            break;
×
478
        default:
×
479
            return Offboard::Result::CommandDenied;
×
480
            break;
481
    }
482

483
    mavlink_message_t message;
×
484
    mavlink_msg_set_position_target_global_int_pack(
×
485
        _system_impl->get_own_system_id(),
×
486
        _system_impl->get_own_component_id(),
×
487
        &message,
488
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
489
        _system_impl->get_system_id(),
×
490
        _system_impl->get_autopilot_id(),
×
491
        frame,
492
        IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
493
        (int32_t)(position_global_yaw.lat_deg * 1.0e7),
×
494
        (int32_t)(position_global_yaw.lon_deg * 1.0e7),
×
495
        position_global_yaw.alt_m,
×
496
        0.0f, // vx
497
        0.0f, // vy
498
        0.0f, // vz
499
        0.0f, // afx
500
        0.0f, // afy
501
        0.0f, // afz
502
        to_rad_from_deg(position_global_yaw.yaw_deg), // yaw
×
503
        0.0f); // yaw_rate
504
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
505
                                                 Offboard::Result::ConnectionError;
×
506
}
507

508
Offboard::Result OffboardImpl::send_velocity_ned()
×
509
{
510
    const static uint16_t IGNORE_X = (1 << 0);
511
    const static uint16_t IGNORE_Y = (1 << 1);
512
    const static uint16_t IGNORE_Z = (1 << 2);
513
    const static uint16_t IGNORE_AX = (1 << 6);
514
    const static uint16_t IGNORE_AY = (1 << 7);
515
    const static uint16_t IGNORE_AZ = (1 << 8);
516
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
517

518
    const auto velocity_ned_yaw = [this]() {
×
519
        std::lock_guard<std::mutex> lock(_mutex);
×
520
        return _velocity_ned_yaw;
×
521
    }();
×
522

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

548
Offboard::Result OffboardImpl::send_position_velocity_ned()
×
549
{
550
    const static uint16_t IGNORE_AX = (1 << 6);
551
    const static uint16_t IGNORE_AY = (1 << 7);
552
    const static uint16_t IGNORE_AZ = (1 << 8);
553
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
554

555
    const auto position_and_velocity = [this]() {
×
556
        std::lock_guard<std::mutex> lock(_mutex);
×
557
        return std::make_pair<>(_position_ned_yaw, _velocity_ned_yaw);
×
558
    }();
×
559

560
    mavlink_message_t message;
×
561
    mavlink_msg_set_position_target_local_ned_pack(
×
562
        _system_impl->get_own_system_id(),
×
563
        _system_impl->get_own_component_id(),
×
564
        &message,
565
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
566
        _system_impl->get_system_id(),
×
567
        _system_impl->get_autopilot_id(),
×
568
        MAV_FRAME_LOCAL_NED,
569
        IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW_RATE,
570
        position_and_velocity.first.north_m,
×
571
        position_and_velocity.first.east_m,
×
572
        position_and_velocity.first.down_m,
×
573
        position_and_velocity.second.north_m_s,
×
574
        position_and_velocity.second.east_m_s,
×
575
        position_and_velocity.second.down_m_s,
×
576
        0.0f, // afx
577
        0.0f, // afy
578
        0.0f, // afz
579
        to_rad_from_deg(position_and_velocity.first.yaw_deg), // yaw
×
580
        0.0f); // yaw_rate
581
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
582
                                                 Offboard::Result::ConnectionError;
×
583
}
584

585
Offboard::Result OffboardImpl::send_position_velocity_acceleration_ned()
×
586
{
587
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
588

589
    std::lock_guard<std::mutex> lock(_mutex);
×
590

591
    mavlink_message_t message;
×
592
    mavlink_msg_set_position_target_local_ned_pack(
×
593
        _system_impl->get_own_system_id(),
×
594
        _system_impl->get_own_component_id(),
×
595
        &message,
596
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
597
        _system_impl->get_system_id(),
×
598
        _system_impl->get_autopilot_id(),
×
599
        MAV_FRAME_LOCAL_NED,
600
        IGNORE_YAW_RATE,
601
        _position_ned_yaw.north_m,
602
        _position_ned_yaw.east_m,
603
        _position_ned_yaw.down_m,
604
        _velocity_ned_yaw.north_m_s,
605
        _velocity_ned_yaw.east_m_s,
606
        _velocity_ned_yaw.down_m_s,
607
        _acceleration_ned.north_m_s2,
608
        _acceleration_ned.east_m_s2,
609
        _acceleration_ned.down_m_s2,
610
        to_rad_from_deg(_position_ned_yaw.yaw_deg), // yaw
611
        0.0f); // yaw_rate
612
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
613
                                                 Offboard::Result::ConnectionError;
×
614
}
615

616
Offboard::Result OffboardImpl::send_acceleration_ned()
×
617
{
618
    const static uint16_t IGNORE_X = (1 << 0);
619
    const static uint16_t IGNORE_Y = (1 << 1);
620
    const static uint16_t IGNORE_Z = (1 << 2);
621
    const static uint16_t IGNORE_VX = (1 << 3);
622
    const static uint16_t IGNORE_VY = (1 << 4);
623
    const static uint16_t IGNORE_VZ = (1 << 5);
624
    const static uint16_t IGNORE_YAW = (1 << 10);
625
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);
626

627
    const auto acceleration_ned = [this]() {
×
628
        std::lock_guard<std::mutex> lock(_mutex);
×
629
        return _acceleration_ned;
×
630
    }();
×
631

632
    mavlink_message_t message;
×
633
    mavlink_msg_set_position_target_local_ned_pack(
×
634
        _system_impl->get_own_system_id(),
×
635
        _system_impl->get_own_component_id(),
×
636
        &message,
637
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
638
        _system_impl->get_system_id(),
×
639
        _system_impl->get_autopilot_id(),
×
640
        MAV_FRAME_LOCAL_NED,
641
        IGNORE_X | IGNORE_Y | IGNORE_Z | IGNORE_VX | IGNORE_VY | IGNORE_VZ | IGNORE_YAW |
642
            IGNORE_YAW_RATE,
643
        0.0f, // x,
644
        0.0f, // y,
645
        0.0f, // z,
646
        0.0f, // vfx
647
        0.0f, // vfy
648
        0.0f, // vfz
649
        acceleration_ned.north_m_s2,
×
650
        acceleration_ned.east_m_s2,
×
651
        acceleration_ned.down_m_s2,
×
652
        0.0f, // yaw
653
        0.0f); // yaw_rate
654
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
655
                                                 Offboard::Result::ConnectionError;
×
656
}
657

658
Offboard::Result OffboardImpl::send_velocity_body()
×
659
{
660
    const static uint16_t IGNORE_X = (1 << 0);
661
    const static uint16_t IGNORE_Y = (1 << 1);
662
    const static uint16_t IGNORE_Z = (1 << 2);
663
    const static uint16_t IGNORE_AX = (1 << 6);
664
    const static uint16_t IGNORE_AY = (1 << 7);
665
    const static uint16_t IGNORE_AZ = (1 << 8);
666
    const static uint16_t IGNORE_YAW = (1 << 10);
667

668
    const auto velocity_body_yawspeed = [this]() {
×
669
        std::lock_guard<std::mutex> lock(_mutex);
×
670
        return _velocity_body_yawspeed;
×
671
    }();
×
672

673
    mavlink_message_t message;
×
674
    mavlink_msg_set_position_target_local_ned_pack(
×
675
        _system_impl->get_own_system_id(),
×
676
        _system_impl->get_own_component_id(),
×
677
        &message,
678
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
679
        _system_impl->get_system_id(),
×
680
        _system_impl->get_autopilot_id(),
×
681
        MAV_FRAME_BODY_NED,
682
        IGNORE_X | IGNORE_Y | IGNORE_Z | IGNORE_AX | IGNORE_AY | IGNORE_AZ | IGNORE_YAW,
683
        0.0f, // x
684
        0.0f, // y
685
        0.0f, // z
686
        velocity_body_yawspeed.forward_m_s,
×
687
        velocity_body_yawspeed.right_m_s,
×
688
        velocity_body_yawspeed.down_m_s,
×
689
        0.0f, // afx
690
        0.0f, // afy
691
        0.0f, // afz
692
        0.0f, // yaw
693
        to_rad_from_deg(velocity_body_yawspeed.yawspeed_deg_s));
×
694
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
695
                                                 Offboard::Result::ConnectionError;
×
696
}
697

698
Offboard::Result OffboardImpl::send_attitude()
×
699
{
700
    const static uint8_t IGNORE_BODY_ROLL_RATE = (1 << 0);
701
    const static uint8_t IGNORE_BODY_PITCH_RATE = (1 << 1);
702
    const static uint8_t IGNORE_BODY_YAW_RATE = (1 << 2);
703

704
    const auto attitude = [this]() {
×
705
        std::lock_guard<std::mutex> lock(_mutex);
×
706
        return _attitude;
×
707
    }();
×
708

709
    const float thrust = _attitude.thrust_value;
×
710
    const float roll = to_rad_from_deg(attitude.roll_deg);
×
711
    const float pitch = to_rad_from_deg(attitude.pitch_deg);
×
712
    const float yaw = to_rad_from_deg(attitude.yaw_deg);
×
713

714
    const double cos_phi_2 = cos(double(roll) / 2.0);
×
715
    const double sin_phi_2 = sin(double(roll) / 2.0);
×
716
    const double cos_theta_2 = cos(double(pitch) / 2.0);
×
717
    const double sin_theta_2 = sin(double(pitch) / 2.0);
×
718
    const double cos_psi_2 = cos(double(yaw) / 2.0);
×
719
    const double sin_psi_2 = sin(double(yaw) / 2.0);
×
720

721
    float q[4];
×
722

723
    q[0] = float(cos_phi_2 * cos_theta_2 * cos_psi_2 + sin_phi_2 * sin_theta_2 * sin_psi_2);
×
724
    q[1] = float(sin_phi_2 * cos_theta_2 * cos_psi_2 - cos_phi_2 * sin_theta_2 * sin_psi_2);
×
725
    q[2] = float(cos_phi_2 * sin_theta_2 * cos_psi_2 + sin_phi_2 * cos_theta_2 * sin_psi_2);
×
726
    q[3] = float(cos_phi_2 * cos_theta_2 * sin_psi_2 - sin_phi_2 * sin_theta_2 * cos_psi_2);
×
727

728
    const float thrust_body[3] = {0.0f, 0.0f, 0.0f};
×
729

730
    mavlink_message_t message;
×
731
    mavlink_msg_set_attitude_target_pack(
×
732
        _system_impl->get_own_system_id(),
×
733
        _system_impl->get_own_component_id(),
×
734
        &message,
735
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
736
        _system_impl->get_system_id(),
×
737
        _system_impl->get_autopilot_id(),
×
738
        IGNORE_BODY_ROLL_RATE | IGNORE_BODY_PITCH_RATE | IGNORE_BODY_YAW_RATE,
739
        q,
740
        0,
741
        0,
742
        0,
743
        thrust,
744
        thrust_body);
745
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
746
                                                 Offboard::Result::ConnectionError;
×
747
}
748

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

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

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

760
    mavlink_message_t message;
×
761
    mavlink_msg_set_attitude_target_pack(
×
762
        _system_impl->get_own_system_id(),
×
763
        _system_impl->get_own_component_id(),
×
764
        &message,
765
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
766
        _system_impl->get_system_id(),
×
767
        _system_impl->get_autopilot_id(),
×
768
        IGNORE_ATTITUDE,
769
        0,
770
        to_rad_from_deg(attitude_rate.roll_deg_s),
×
771
        to_rad_from_deg(attitude_rate.pitch_deg_s),
×
772
        to_rad_from_deg(attitude_rate.yaw_deg_s),
×
773
        _attitude_rate.thrust_value,
774
        thrust_body);
775
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
776
                                                 Offboard::Result::ConnectionError;
×
777
}
778

779
Offboard::Result
780
OffboardImpl::send_actuator_control_message(const float* controls, uint8_t group_number)
×
781
{
782
    mavlink_message_t message;
×
783
    mavlink_msg_set_actuator_control_target_pack(
×
784
        _system_impl->get_own_system_id(),
×
785
        _system_impl->get_own_component_id(),
×
786
        &message,
787
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
×
788
        group_number,
789
        _system_impl->get_system_id(),
×
790
        _system_impl->get_autopilot_id(),
×
791
        controls);
792
    return _system_impl->send_message(message) ? Offboard::Result::Success :
×
793
                                                 Offboard::Result::ConnectionError;
×
794
}
795

796
Offboard::Result OffboardImpl::send_actuator_control()
×
797
{
798
    std::lock_guard<std::mutex> lock(_mutex);
×
799

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

803
        for (unsigned j = 0; j < 8; ++j) {
×
804
            if (std::isnan(_actuator_control.groups[i].controls[j])) {
×
805
                _actuator_control.groups[i].controls[j] = 0.0f;
×
806
            }
807
        }
808
        auto result = send_actuator_control_message(&_actuator_control.groups[i].controls[0], i);
×
809

810
        if (result != Offboard::Result::Success) {
×
811
            return result;
×
812
        }
813
    }
814

815
    return Offboard::Result::Success;
×
816
}
817

818
void OffboardImpl::process_heartbeat(const mavlink_message_t& message)
×
819
{
820
    // Process only Heartbeat coming from the autopilot
821
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
×
822
        return;
×
823
    }
824

825
    mavlink_heartbeat_t heartbeat;
×
826
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
×
827

828
    bool offboard_mode_active = false;
×
829
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
×
830
        FlightMode flight_mode = to_flight_mode_from_custom_mode(
×
831
            _system_impl->autopilot(), _system_impl->get_vehicle_type(), heartbeat.custom_mode);
×
832

833
        if (flight_mode == FlightMode::Offboard) {
×
834
            offboard_mode_active = true;
×
835
        }
836
    }
837

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

853
void OffboardImpl::stop_sending_setpoints()
×
854
{
855
    // We assume that we already acquired the mutex in this function.
856

857
    if (_call_every_cookie != nullptr) {
×
858
        _system_impl->remove_call_every(_call_every_cookie);
×
859
        _call_every_cookie = nullptr;
×
860
    }
861
    _mode = Mode::NotActive;
×
862
}
×
863

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

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