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

mavlink / MAVSDK / 16665088909

01 Aug 2025 02:55AM UTC coverage: 46.166% (-0.1%) from 46.31%
16665088909

push

github

web-flow
Merge pull request #2630 from mavlink/pr-segfault-fixes

Stack-use-after-free and thread-safety fixes, CI additions, clang-format-19

241 of 320 new or added lines in 32 files covered. (75.31%)

39 existing lines in 10 files now uncovered.

16101 of 34876 relevant lines covered (46.17%)

361.1 hits per line

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

0.0
/src/mavsdk/plugins/mission/mission_impl.cpp
1
#include "mission_impl.h"
2
#include "system.h"
3
#include "unused.h"
4
#include "callback_list.tpp"
5
#include <algorithm>
6
#include <cmath>
7

8
namespace mavsdk {
9

10
template class CallbackList<Mission::MissionProgress>;
11

12
using MissionItem = Mission::MissionItem;
13
using CameraAction = Mission::MissionItem::CameraAction;
14
using VehicleAction = Mission::MissionItem::VehicleAction;
15

16
MissionImpl::MissionImpl(System& system) : PluginImplBase(system)
×
17
{
18
    _system_impl->register_plugin(this);
×
19
}
×
20

21
MissionImpl::MissionImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
×
22
{
23
    _system_impl->register_plugin(this);
×
24
}
×
25

26
MissionImpl::~MissionImpl()
×
27
{
28
    _system_impl->unregister_plugin(this);
×
29
}
×
30

31
void MissionImpl::init()
×
32
{
33
    _system_impl->register_mavlink_message_handler(
×
34
        MAVLINK_MSG_ID_MISSION_CURRENT,
35
        [this](const mavlink_message_t& message) { process_mission_current(message); },
×
36
        this);
37

38
    _system_impl->register_mavlink_message_handler(
×
39
        MAVLINK_MSG_ID_MISSION_ITEM_REACHED,
40
        [this](const mavlink_message_t& message) { process_mission_item_reached(message); },
×
41
        this);
42
}
×
43

44
void MissionImpl::enable() {}
×
45

46
void MissionImpl::disable()
×
47
{
48
    reset_mission_progress();
×
49
}
×
50

51
void MissionImpl::deinit()
×
52
{
53
    _system_impl->unregister_timeout_handler(_timeout_cookie);
×
54
    _system_impl->unregister_all_mavlink_message_handlers(this);
×
55
}
×
56

57
void MissionImpl::reset_mission_progress()
×
58
{
59
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
60
    _mission_data.last_current_mavlink_mission_item = -1;
×
61
    _mission_data.last_reached_mavlink_mission_item = -1;
×
62
    _mission_data.last_current_reported_mission_item = -1;
×
63
    _mission_data.last_total_reported_mission_item = -1;
×
64
}
×
65

66
void MissionImpl::process_mission_current(const mavlink_message_t& message)
×
67
{
68
    mavlink_mission_current_t mission_current;
69
    mavlink_msg_mission_current_decode(&message, &mission_current);
×
70

71
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
72
    _mission_data.last_current_mavlink_mission_item = mission_current.seq;
×
73
    _mission_data.mission_state = mission_current.mission_state;
×
74
    report_progress_locked();
×
75
}
×
76

77
void MissionImpl::process_mission_item_reached(const mavlink_message_t& message)
×
78
{
79
    mavlink_mission_item_reached_t mission_item_reached;
80
    mavlink_msg_mission_item_reached_decode(&message, &mission_item_reached);
×
81

82
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
83
    _mission_data.last_reached_mavlink_mission_item = mission_item_reached.seq;
×
84
    report_progress_locked();
×
85
}
×
86

87
Mission::Result MissionImpl::upload_mission(const Mission::MissionPlan& mission_plan)
×
88
{
89
    auto prom = std::promise<Mission::Result>();
×
90
    auto fut = prom.get_future();
×
91

92
    upload_mission_async(mission_plan, [&prom](Mission::Result result) { prom.set_value(result); });
×
93
    return fut.get();
×
94
}
×
95

96
void MissionImpl::upload_mission_async(
×
97
    const Mission::MissionPlan& mission_plan, const Mission::ResultCallback& callback)
98
{
99
    if (_mission_data.last_upload.lock()) {
×
100
        _system_impl->call_user_callback([callback]() {
×
101
            if (callback) {
102
                callback(Mission::Result::Busy);
103
            }
104
        });
105
        return;
×
106
    }
107

108
    reset_mission_progress();
×
109

110
    const auto int_items = convert_to_int_items(mission_plan.mission_items);
×
111

112
    _mission_data.last_upload = _system_impl->mission_transfer_client().upload_items_async(
×
113
        MAV_MISSION_TYPE_MISSION,
114
        _system_impl->get_system_id(),
×
115
        int_items,
116
        [this, callback](MavlinkMissionTransferClient::Result result) {
×
117
            auto converted_result = convert_result(result);
×
118
            _system_impl->call_user_callback([callback, converted_result]() {
×
119
                if (callback) {
120
                    callback(converted_result);
121
                }
122
            });
123
        });
×
124
}
×
125

126
void MissionImpl::upload_mission_with_progress_async(
×
127
    const Mission::MissionPlan& mission_plan,
128
    const Mission::UploadMissionWithProgressCallback callback)
129
{
130
    if (_mission_data.last_upload.lock()) {
×
131
        _system_impl->call_user_callback([callback]() {
×
132
            if (callback) {
133
                callback(Mission::Result::Busy, Mission::ProgressData{});
134
            }
135
        });
136
        return;
×
137
    }
138

139
    reset_mission_progress();
×
140

141
    const auto int_items = convert_to_int_items(mission_plan.mission_items);
×
142

143
    _mission_data.last_upload = _system_impl->mission_transfer_client().upload_items_async(
×
144
        MAV_MISSION_TYPE_MISSION,
145
        _system_impl->get_system_id(),
×
146
        int_items,
147
        [this, callback](MavlinkMissionTransferClient::Result result) {
×
148
            auto converted_result = convert_result(result);
×
149
            _system_impl->call_user_callback([callback, converted_result]() {
×
150
                if (callback) {
151
                    callback(converted_result, Mission::ProgressData{});
152
                }
153
            });
154
        },
×
155
        [this, callback](float progress) {
×
156
            _system_impl->call_user_callback([callback, progress]() {
×
157
                if (callback) {
158
                    callback(Mission::Result::Next, Mission::ProgressData{progress});
159
                }
160
            });
161
        });
×
162
}
×
163

164
Mission::Result MissionImpl::cancel_mission_upload() const
×
165
{
166
    auto ptr = _mission_data.last_upload.lock();
×
167
    if (ptr) {
×
168
        ptr->cancel();
×
169
    } else {
170
        LogWarn() << "No mission upload to cancel... ignoring";
×
171
    }
172

173
    return Mission::Result::Success;
×
174
}
×
175

176
std::pair<Mission::Result, Mission::MissionPlan> MissionImpl::download_mission()
×
177
{
178
    auto prom = std::promise<std::pair<Mission::Result, Mission::MissionPlan>>();
×
179
    auto fut = prom.get_future();
×
180

181
    download_mission_async(
×
182
        [&prom](Mission::Result result, const Mission::MissionPlan& mission_plan) {
×
183
            prom.set_value(std::make_pair<>(result, mission_plan));
×
184
        });
×
185
    return fut.get();
×
186
}
×
187

188
void MissionImpl::download_mission_async(const Mission::DownloadMissionCallback& callback)
×
189
{
190
    if (_mission_data.last_download.lock()) {
×
191
        _system_impl->call_user_callback([callback]() {
×
192
            if (callback) {
193
                Mission::MissionPlan mission_plan{};
194
                callback(Mission::Result::Busy, mission_plan);
195
            }
196
        });
197
        return;
×
198
    }
199

200
    _mission_data.last_download = _system_impl->mission_transfer_client().download_items_async(
×
201
        MAV_MISSION_TYPE_MISSION,
202
        _system_impl->get_system_id(),
×
203
        [this, callback](
×
204
            MavlinkMissionTransferClient::Result result,
205
            std::vector<MavlinkMissionTransferClient::ItemInt> items) {
×
206
            auto result_and_items = convert_to_result_and_mission_items(result, items);
×
207
            _system_impl->call_user_callback([callback, result_and_items]() {
×
208
                callback(result_and_items.first, result_and_items.second);
209
            });
210
        });
×
211
}
212

213
void MissionImpl::download_mission_with_progress_async(
×
214
    const Mission::DownloadMissionWithProgressCallback callback)
215
{
216
    if (_mission_data.last_download.lock()) {
×
217
        _system_impl->call_user_callback([callback]() {
×
218
            if (callback) {
219
                Mission::ProgressDataOrMission progress_data_or_mission{};
220
                progress_data_or_mission.has_mission = false;
221
                progress_data_or_mission.has_progress = false;
222
                callback(Mission::Result::Busy, progress_data_or_mission);
223
            }
224
        });
225
        return;
×
226
    }
227

228
    _mission_data.last_download = _system_impl->mission_transfer_client().download_items_async(
×
229
        MAV_MISSION_TYPE_MISSION,
230
        _system_impl->get_system_id(),
×
231
        [this, callback](
×
232
            MavlinkMissionTransferClient::Result result,
233
            const std::vector<MavlinkMissionTransferClient::ItemInt>& items) {
×
234
            auto result_and_items = convert_to_result_and_mission_items(result, items);
×
235
            _system_impl->call_user_callback([callback, result_and_items]() {
×
236
                if (result_and_items.first == Mission::Result::Success) {
237
                    Mission::ProgressDataOrMission progress_data_or_mission{};
238
                    progress_data_or_mission.has_mission = true;
239
                    progress_data_or_mission.mission_plan = result_and_items.second;
240
                    callback(Mission::Result::Next, progress_data_or_mission);
241
                }
242

243
                callback(result_and_items.first, Mission::ProgressDataOrMission{});
244
            });
245
        },
×
246
        [this, callback](float progress) {
×
247
            _system_impl->call_user_callback([callback, progress]() {
×
248
                Mission::ProgressDataOrMission progress_data_or_mission{};
249
                progress_data_or_mission.has_progress = true;
250
                progress_data_or_mission.progress = progress;
251
                callback(Mission::Result::Next, progress_data_or_mission);
252
            });
253
        });
×
254
}
255

256
Mission::Result MissionImpl::cancel_mission_download() const
×
257
{
258
    auto ptr = _mission_data.last_download.lock();
×
259
    if (ptr) {
×
260
        ptr->cancel();
×
261
    } else {
262
        LogWarn() << "No mission download to cancel... ignoring";
×
263
    }
264

265
    return Mission::Result::Success;
×
266
}
×
267

268
Mission::Result MissionImpl::set_return_to_launch_after_mission(bool enable_rtl)
×
269
{
270
    _enable_return_to_launch_after_mission = enable_rtl;
×
271
    return Mission::Result::Success;
×
272
}
273

274
std::pair<Mission::Result, bool> MissionImpl::get_return_to_launch_after_mission()
×
275
{
276
    return std::make_pair<>(Mission::Result::Success, _enable_return_to_launch_after_mission);
×
277
}
278

279
bool MissionImpl::has_valid_position(const MissionItem& item)
×
280
{
281
    return std::isfinite(item.latitude_deg) && std::isfinite(item.longitude_deg) &&
×
282
           std::isfinite(item.relative_altitude_m);
×
283
}
284

285
float MissionImpl::hold_time(const MissionItem& item)
×
286
{
287
    float hold_time_s;
288
    if (item.is_fly_through) {
×
289
        hold_time_s = 0.0f;
×
290
    } else {
291
        hold_time_s = 0.5f;
×
292
    }
293

294
    return hold_time_s;
×
295
}
296

297
float MissionImpl::acceptance_radius(const MissionItem& item)
×
298
{
299
    float acceptance_radius_m;
300
    if (std::isfinite(item.acceptance_radius_m)) {
×
301
        acceptance_radius_m = item.acceptance_radius_m;
×
302
    } else if (item.is_fly_through) {
×
303
        // _acceptance_radius_m is 0, determine the radius using fly_through
304
        acceptance_radius_m = 3.0f;
×
305
    } else {
306
        // _acceptance_radius_m is 0, determine the radius using fly_through
307
        acceptance_radius_m = 1.0f;
×
308
    }
309

310
    return acceptance_radius_m;
×
311
}
312

313
std::vector<MavlinkMissionTransferClient::ItemInt>
314
MissionImpl::convert_to_int_items(const std::vector<MissionItem>& mission_items)
×
315
{
316
    std::vector<MavlinkMissionTransferClient::ItemInt> int_items;
×
317

318
    bool last_position_valid = false; // This flag is to protect us from using an invalid x/y.
×
319

320
    unsigned item_i = 0;
×
321
    _mission_data.mavlink_mission_item_to_mission_item_indices.clear();
×
322
    _mission_data.gimbal_v2_in_control = false;
×
323

324
    for (const auto& item : mission_items) {
×
325
        if (item.vehicle_action == VehicleAction::Takeoff) {
×
326
            // There is a vehicle action that we need to send.
327

328
            // Current is the 0th waypoint
329
            uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
330

331
            uint8_t autocontinue = 1;
×
332

333
            const int32_t x = int32_t(std::round(item.latitude_deg * 1e7));
×
334
            const int32_t y = int32_t(std::round(item.longitude_deg * 1e7));
×
335
            float z = item.relative_altitude_m;
×
336
            MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT;
×
337

338
            MavlinkMissionTransferClient::ItemInt next_item{
×
339
                static_cast<uint16_t>(int_items.size()),
×
340
                (uint8_t)frame,
341
                MAV_CMD_NAV_TAKEOFF,
342
                current,
343
                autocontinue,
344
                NAN,
345
                NAN,
346
                NAN,
347
                NAN,
348
                x,
349
                y,
350
                z,
351
                MAV_MISSION_TYPE_MISSION};
×
352

353
            _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
354
            int_items.push_back(next_item);
×
355
        } else {
356
            if (has_valid_position(item)) {
×
357
                // Current is the 0th waypoint
358
                const uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
359

360
                const int32_t x = int32_t(std::round(item.latitude_deg * 1e7));
×
361
                const int32_t y = int32_t(std::round(item.longitude_deg * 1e7));
×
362
                const float z = item.relative_altitude_m;
×
363

364
                MavlinkMissionTransferClient::ItemInt next_item{
×
365
                    static_cast<uint16_t>(int_items.size()),
×
366
                    static_cast<uint8_t>(MAV_FRAME_GLOBAL_RELATIVE_ALT_INT),
367
                    static_cast<uint8_t>(MAV_CMD_NAV_WAYPOINT),
368
                    current,
369
                    1, // autocontinue
370
                    hold_time(item),
×
371
                    acceptance_radius(item),
×
372
                    0.0f,
373
                    item.yaw_deg,
×
374
                    x,
375
                    y,
376
                    z,
377
                    MAV_MISSION_TYPE_MISSION};
×
378

379
                last_position_valid = true; // because we checked has_valid_position
×
380

381
                _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
382
                int_items.push_back(next_item);
×
383
            }
384
        }
385

386
        if (std::isfinite(item.speed_m_s)) {
×
387
            // The speed has changed, we need to add a speed command.
388

389
            // Current is the 0th waypoint
390
            uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
391

392
            uint8_t autocontinue = 1;
×
393

394
            MavlinkMissionTransferClient::ItemInt next_item{
×
395
                static_cast<uint16_t>(int_items.size()),
×
396
                MAV_FRAME_MISSION,
397
                MAV_CMD_DO_CHANGE_SPEED,
398
                current,
399
                autocontinue,
400
                1.0f, // ground speed
401
                item.speed_m_s,
×
402
                -1.0f, // no throttle change
403
                0.0f, // absolute
404
                0,
405
                0,
406
                NAN,
407
                MAV_MISSION_TYPE_MISSION};
×
408

409
            _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
410
            int_items.push_back(next_item);
×
411
        }
412

413
        if (std::isfinite(item.gimbal_yaw_deg) || std::isfinite(item.gimbal_pitch_deg)) {
×
414
            if (!_mission_data.gimbal_v2_in_control) {
×
415
                acquire_gimbal_control_v2(int_items, item_i);
×
416
                _mission_data.gimbal_v2_in_control = true;
×
417
            }
418
            add_gimbal_items_v2(int_items, item_i, item.gimbal_pitch_deg, item.gimbal_yaw_deg);
×
419
        }
420

421
        // A loiter time of NAN is ignored but also a loiter time of 0 doesn't
422
        // make any sense and should be discarded.
423
        if (std::isfinite(item.loiter_time_s) && item.loiter_time_s > 0.0f) {
×
424
            if (!last_position_valid) {
×
425
                // In the case where we get a delay without a previous position, we will have to
426
                // ignore it.
427
                LogErr() << "Can't set camera action delay without previous position set.";
×
428

429
            } else {
430
                // Current is the 0th waypoint
431
                uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
432

433
                uint8_t autocontinue = 1;
×
434

435
                MavlinkMissionTransferClient::ItemInt next_item{
×
436
                    static_cast<uint16_t>(int_items.size()),
×
437
                    MAV_FRAME_MISSION,
438
                    MAV_CMD_NAV_DELAY,
439
                    current,
440
                    autocontinue,
441
                    item.loiter_time_s, // loiter time in seconds
×
442
                    -1, // no specified hour
443
                    -1, // no specified minute
444
                    -1, // no specified second
445
                    0,
446
                    0,
447
                    0,
448
                    MAV_MISSION_TYPE_MISSION};
×
449

450
                _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
451
                int_items.push_back(next_item);
×
452
            }
453

454
            if (item.is_fly_through) {
×
455
                LogWarn() << "Conflicting options set: fly_through=true and loiter_time>0.";
×
456
            }
457
        }
458

459
        if (item.camera_action != CameraAction::None) {
×
460
            // Current is the 0th waypoint
461
            uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
462
            uint8_t autocontinue = 1;
×
463

464
            uint16_t command = 0;
×
465
            float param1 = NAN;
×
466
            float param2 = NAN;
×
467
            float param3 = NAN;
×
468
            float param4 = NAN;
×
469
            switch (item.camera_action) {
×
470
                case CameraAction::TakePhoto:
×
471
                    command = MAV_CMD_IMAGE_START_CAPTURE;
×
472
                    param1 = 0.0f; // all camera IDs
×
473
                    param2 = 0.0f; // no duration, take only one picture
×
474
                    param3 = 1.0f; // only take one picture
×
475
                    param4 = 0.0f; // no capture sequence
×
476
                    break;
×
477
                case CameraAction::StartPhotoInterval:
×
478
                    command = MAV_CMD_IMAGE_START_CAPTURE;
×
479
                    param1 = 0.0f; // all camera IDs
×
480
                    param2 = item.camera_photo_interval_s;
×
481
                    param3 = 0.0f; // unlimited photos
×
482
                    param4 = 0.0f; // no capture sequence
×
483
                    break;
×
484
                case CameraAction::StopPhotoInterval:
×
485
                    command = MAV_CMD_IMAGE_STOP_CAPTURE;
×
486
                    param1 = 0.0f; // all camera IDs
×
487
                    break;
×
488
                case CameraAction::StartVideo:
×
489
                    command = MAV_CMD_VIDEO_START_CAPTURE;
×
490
                    param1 = 0.0f; // all camera IDs
×
491
                    param2 = 0.0f; // no status frequency messages to send
×
492
                    break;
×
493
                case CameraAction::StopVideo:
×
494
                    command = MAV_CMD_VIDEO_STOP_CAPTURE;
×
495
                    param1 = 0.0f; // all camera IDs
×
496
                    break;
×
497
                case CameraAction::StartPhotoDistance:
×
498
                    command = MAV_CMD_DO_SET_CAM_TRIGG_DIST;
×
499
                    if (std::isfinite(item.camera_photo_distance_m)) {
×
500
                        LogErr() << "No photo distance specified";
×
501
                    }
502
                    param1 = item.camera_photo_distance_m; // enable with distance
×
503
                    param2 = 0.0f; // ignore
×
504
                    param3 = 1.0f; // trigger
×
505
                    break;
×
506
                case CameraAction::StopPhotoDistance:
×
507
                    command = MAV_CMD_DO_SET_CAM_TRIGG_DIST;
×
508
                    param1 = 0.0f; // stop
×
509
                    param2 = 0.0f; // ignore
×
510
                    param3 = 0.0f; // no trigger
×
511
                    break;
×
512
                default:
×
513
                    LogErr() << "Camera action not supported";
×
514
                    break;
×
515
            }
516

517
            MavlinkMissionTransferClient::ItemInt next_item{
×
518
                static_cast<uint16_t>(int_items.size()),
×
519
                MAV_FRAME_MISSION,
520
                command,
521
                current,
522
                autocontinue,
523
                param1,
524
                param2,
525
                param3,
526
                param4,
527
                0,
528
                0,
529
                NAN,
530
                MAV_MISSION_TYPE_MISSION};
×
531

532
            _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
533
            int_items.push_back(next_item);
×
534
        }
535

536
        if (item.vehicle_action != VehicleAction::None &&
×
537
            item.vehicle_action != VehicleAction::Takeoff) {
×
538
            // There is a vehicle action that we need to send.
539

540
            // Current is the 0th waypoint
541
            uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
542

543
            uint8_t autocontinue = 1;
×
544

545
            uint16_t command = 0;
×
546
            float param1 = NAN;
×
547
            float param2 = NAN;
×
548
            float param3 = NAN;
×
549
            switch (item.vehicle_action) {
×
550
                case VehicleAction::Land:
×
551
                    command = MAV_CMD_NAV_LAND; // Land at current position with same heading
×
552
                    break;
×
553
                case VehicleAction::TransitionToFw:
×
554
                    command = MAV_CMD_DO_VTOL_TRANSITION; // Do transition
×
555
                    param1 = MAV_VTOL_STATE_FW; // Target state is Fixed-Wing
×
556
                    param2 = 0; // Normal transition
×
557
                    break;
×
558
                case VehicleAction::TransitionToMc:
×
559
                    command = MAV_CMD_DO_VTOL_TRANSITION;
×
560
                    param1 = MAV_VTOL_STATE_MC; // Target state is Multi-Copter
×
561
                    param2 = 0; // Normal transition
×
562
                    break;
×
563
                default:
×
564
                    LogErr() << "Error: vehicle action not supported";
×
565
                    break;
×
566
            }
567

568
            const int32_t x = int32_t(std::round(item.latitude_deg * 1e7));
×
569
            const int32_t y = int32_t(std::round(item.longitude_deg * 1e7));
×
570
            float z = item.relative_altitude_m;
×
571
            MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT;
×
572

573
            if (command == MAV_CMD_NAV_LAND) {
×
574
                z = 0;
×
575
            }
576

577
            if (command == MAV_CMD_DO_VTOL_TRANSITION) {
×
578
                frame = MAV_FRAME_MISSION;
×
579
            }
580

581
            MavlinkMissionTransferClient::ItemInt next_item{
×
582
                static_cast<uint16_t>(int_items.size()),
×
583
                (uint8_t)frame,
584
                command,
585
                current,
586
                autocontinue,
587
                param1,
588
                param2,
589
                param3,
590
                NAN,
591
                x,
592
                y,
593
                z,
594
                MAV_MISSION_TYPE_MISSION};
×
595

596
            _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
597
            int_items.push_back(next_item);
×
598
        }
599

600
        ++item_i;
×
601
    }
602

603
    // We need to decrement the item_i again because it was increased in the loop above
604
    // but the last items below still belong to the last mission item.
605
    --item_i;
×
606

607
    if (_mission_data.gimbal_v2_in_control) {
×
608
        release_gimbal_control_v2(int_items, item_i);
×
609
        _mission_data.gimbal_v2_in_control = false;
×
610
    }
611

612
    if (_enable_return_to_launch_after_mission) {
×
613
        MavlinkMissionTransferClient::ItemInt next_item{
×
614
            static_cast<uint16_t>(int_items.size()),
×
615
            MAV_FRAME_MISSION,
616
            MAV_CMD_NAV_RETURN_TO_LAUNCH,
617
            0, // current
618
            1, // autocontinue
619
            NAN, // loiter time in seconds
620
            NAN, // empty
621
            NAN, // radius around waypoint in meters ?
622
            NAN, // loiter at center of waypoint
623
            0,
624
            0,
625
            0,
626
            MAV_MISSION_TYPE_MISSION};
×
627

628
        _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
629
        int_items.push_back(next_item);
×
630
    }
631
    return int_items;
×
632
}
633

634
std::pair<Mission::Result, Mission::MissionPlan> MissionImpl::convert_to_result_and_mission_items(
×
635
    MavlinkMissionTransferClient::Result result,
636
    const std::vector<MavlinkMissionTransferClient::ItemInt>& int_items)
637
{
638
    std::pair<Mission::Result, Mission::MissionPlan> result_pair;
×
639

640
    result_pair.first = convert_result(result);
×
641
    if (result_pair.first != Mission::Result::Success) {
×
642
        return result_pair;
×
643
    }
644

645
    _mission_data.mavlink_mission_item_to_mission_item_indices.clear();
×
646

647
    Mission::DownloadMissionCallback callback;
×
648
    {
649
        _enable_return_to_launch_after_mission = false;
×
650

651
        MissionItem new_mission_item{};
×
652
        bool have_set_position = false;
×
653

654
        for (const auto& int_item : int_items) {
×
655
            LogDebug() << "Assembling Message: " << int(int_item.seq);
×
656

657
            if (int_item.command == MAV_CMD_NAV_WAYPOINT ||
×
658
                int_item.command == MAV_CMD_NAV_TAKEOFF) {
×
659
                if (int_item.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
×
660
                    LogErr() << "Waypoint frame not supported unsupported";
×
661
                    result_pair.first = Mission::Result::Unsupported;
×
662
                    break;
×
663
                }
664

665
                if (have_set_position) {
×
666
                    // When a new position comes in, create next mission item.
667
                    result_pair.second.mission_items.push_back(new_mission_item);
×
668
                    new_mission_item = {};
×
669
                    have_set_position = false;
×
670
                }
671

672
                new_mission_item.latitude_deg = double(int_item.x) * 1e-7;
×
673
                new_mission_item.longitude_deg = double(int_item.y) * 1e-7;
×
674
                new_mission_item.relative_altitude_m = int_item.z;
×
675
                new_mission_item.yaw_deg = int_item.param4;
×
676

677
                if (int_item.command == MAV_CMD_NAV_TAKEOFF) {
×
678
                    new_mission_item.acceptance_radius_m = 1;
×
679
                    new_mission_item.is_fly_through = false;
×
680
                    new_mission_item.vehicle_action = VehicleAction::Takeoff;
×
681
                } else {
682
                    new_mission_item.acceptance_radius_m = int_item.param2;
×
683
                    new_mission_item.is_fly_through = !(int_item.param1 > 0);
×
684
                }
685

686
                have_set_position = true;
×
687

688
            } else if (int_item.command == MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW) {
×
689
                if (int_item.x !=
×
690
                    (GIMBAL_MANAGER_FLAGS_ROLL_LOCK | GIMBAL_MANAGER_FLAGS_PITCH_LOCK)) {
691
                    LogErr() << "Gimbal do pitchyaw flags unsupported";
×
692
                    result_pair.first = Mission::Result::Unsupported;
×
693
                    break;
×
694
                }
695

696
                new_mission_item.gimbal_pitch_deg = int_item.param1;
×
697
                new_mission_item.gimbal_yaw_deg = int_item.param2;
×
698

699
            } else if (int_item.command == MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE) {
×
700
                // We need to ignore it in order to not throw an "Unsupported" error
701
                continue;
×
702

703
            } else if (int_item.command == MAV_CMD_IMAGE_START_CAPTURE) {
×
704
                if (int_item.param2 > 0 && int(int_item.param3) == 0) {
×
705
                    new_mission_item.camera_action = CameraAction::StartPhotoInterval;
×
706
                    new_mission_item.camera_photo_interval_s = double(int_item.param2);
×
707
                } else if (int(int_item.param2) == 0 && int(int_item.param3) == 1) {
×
708
                    new_mission_item.camera_action = CameraAction::TakePhoto;
×
709
                } else {
710
                    LogErr() << "Mission item START_CAPTURE params unsupported.";
×
711
                    result_pair.first = Mission::Result::Unsupported;
×
712
                    break;
×
713
                }
714

715
            } else if (int_item.command == MAV_CMD_IMAGE_STOP_CAPTURE) {
×
716
                new_mission_item.camera_action = CameraAction::StopPhotoInterval;
×
717

718
            } else if (int_item.command == MAV_CMD_VIDEO_START_CAPTURE) {
×
719
                new_mission_item.camera_action = CameraAction::StartVideo;
×
720

721
            } else if (int_item.command == MAV_CMD_VIDEO_STOP_CAPTURE) {
×
722
                new_mission_item.camera_action = CameraAction::StopVideo;
×
723

724
            } else if (int_item.command == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
×
725
                if (!std::isfinite(int_item.param1)) {
×
726
                    LogErr() << "Trigger distance in SET_CAM_TRIGG_DIST not finite.";
×
727
                    result_pair.first = Mission::Result::Unsupported;
×
728
                    break;
×
729
                } else if (static_cast<int>(int_item.param1) > 0.0f) {
×
730
                    new_mission_item.camera_action = CameraAction::StartPhotoDistance;
×
731
                    new_mission_item.camera_photo_distance_m = int_item.param1;
×
732
                } else {
733
                    new_mission_item.camera_action = CameraAction::StopPhotoDistance;
×
734
                }
735

736
            } else if (int_item.command == MAV_CMD_NAV_TAKEOFF) {
×
737
                new_mission_item.vehicle_action = VehicleAction::Takeoff;
×
738
            } else if (int_item.command == MAV_CMD_NAV_LAND) {
×
739
                new_mission_item.vehicle_action = VehicleAction::Land;
×
740
            } else if (int_item.command == MAV_CMD_DO_VTOL_TRANSITION) {
×
741
                if (int_item.param1 == MAV_VTOL_STATE_FW) {
×
742
                    new_mission_item.vehicle_action = VehicleAction::TransitionToFw;
×
743
                } else {
744
                    new_mission_item.vehicle_action = VehicleAction::TransitionToMc;
×
745
                }
746

747
            } else if (int_item.command == MAV_CMD_DO_CHANGE_SPEED) {
×
748
                if (int(int_item.param1) == 1 && int_item.param3 < 0 && int(int_item.param4) == 0) {
×
749
                    new_mission_item.speed_m_s = int_item.param2;
×
750
                } else {
751
                    LogErr() << "Mission item DO_CHANGE_SPEED params unsupported";
×
752
                    result_pair.first = Mission::Result::Unsupported;
×
753
                    break;
×
754
                }
755

756
            } else if (int_item.command == MAV_CMD_NAV_LOITER_TIME) {
×
757
                // MAVSDK doesn't use LOITER_TIME anymore, but it is possible
758
                // a mission still uses it
759
                new_mission_item.loiter_time_s = int_item.param1;
×
760

761
            } else if (int_item.command == MAV_CMD_NAV_DELAY) {
×
762
                if (int_item.param1 != -1) {
×
763
                    // use delay in seconds directly
764
                    new_mission_item.loiter_time_s = int_item.param1;
×
765
                } else {
766
                    // TODO: we should support this by converting
767
                    // time of day data to delay in seconds
768
                    // leaving it out for now because a portable implementation
769
                    // is not trivial
770
                    LogErr() << "Mission item NAV_DELAY params unsupported";
×
771
                    result_pair.first = Mission::Result::Unsupported;
×
772
                    break;
×
773
                }
774

775
            } else if (int_item.command == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
×
776
                _enable_return_to_launch_after_mission = true;
×
777

778
            } else {
779
                LogErr() << "UNSUPPORTED mission item command (" << int_item.command << ")";
×
780
                result_pair.first = Mission::Result::Unsupported;
×
781
                break;
×
782
            }
783

784
            _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(
×
785
                result_pair.second.mission_items.size());
×
786
        }
787

788
        // Don't forget to add last mission item.
789
        result_pair.second.mission_items.push_back(new_mission_item);
×
790
    }
UNCOV
791
    return result_pair;
×
792
}
×
793

794
Mission::Result MissionImpl::start_mission()
×
795
{
796
    auto prom = std::promise<Mission::Result>();
×
797
    auto fut = prom.get_future();
×
798

799
    start_mission_async([&prom](Mission::Result result) { prom.set_value(result); });
×
800
    return fut.get();
×
801
}
×
802

803
void MissionImpl::start_mission_async(const Mission::ResultCallback& callback)
×
804
{
805
    _system_impl->set_flight_mode_async(
×
806
        FlightMode::Mission, [this, callback](MavlinkCommandSender::Result result, float) {
×
807
            report_flight_mode_change(callback, result);
×
808
        });
×
809
}
×
810

811
Mission::Result MissionImpl::pause_mission()
×
812
{
813
    auto prom = std::promise<Mission::Result>();
×
814
    auto fut = prom.get_future();
×
815

816
    pause_mission_async([&prom](Mission::Result result) { prom.set_value(result); });
×
817
    return fut.get();
×
818
}
×
819

820
void MissionImpl::pause_mission_async(const Mission::ResultCallback& callback)
×
821
{
822
    _system_impl->set_flight_mode_async(
×
823
        FlightMode::Hold, [this, callback](MavlinkCommandSender::Result result, float) {
×
824
            report_flight_mode_change(callback, result);
×
825
        });
×
826
}
×
827

828
void MissionImpl::report_flight_mode_change(
×
829
    Mission::ResultCallback callback, MavlinkCommandSender::Result result)
830
{
831
    if (!callback) {
×
832
        return;
×
833
    }
834

835
    _system_impl->call_user_callback(
×
836
        [callback, result]() { callback(command_result_to_mission_result(result)); });
837
}
838

839
Mission::Result MissionImpl::command_result_to_mission_result(MavlinkCommandSender::Result result)
×
840
{
841
    switch (result) {
×
842
        case MavlinkCommandSender::Result::Success:
×
843
            return Mission::Result::Success;
×
844
        case MavlinkCommandSender::Result::NoSystem:
×
845
            return Mission::Result::NoSystem;
×
846
        case MavlinkCommandSender::Result::ConnectionError:
×
847
            return Mission::Result::Error;
×
848
        case MavlinkCommandSender::Result::Busy:
×
849
            return Mission::Result::Busy;
×
850
        case MavlinkCommandSender::Result::TemporarilyRejected:
×
851
            // FALLTHROUGH
852
        case MavlinkCommandSender::Result::Denied:
853
            return Mission::Result::Denied;
×
854
        case MavlinkCommandSender::Result::Timeout:
×
855
            return Mission::Result::Timeout;
×
856
        case MavlinkCommandSender::Result::InProgress:
×
857
            return Mission::Result::Busy;
×
858
        case MavlinkCommandSender::Result::UnknownError:
×
859
            return Mission::Result::Unknown;
×
860
        default:
×
861
            return Mission::Result::Unknown;
×
862
    }
863
}
864

865
Mission::Result MissionImpl::clear_mission()
×
866
{
867
    auto prom = std::promise<Mission::Result>();
×
868
    auto fut = prom.get_future();
×
869

870
    clear_mission_async([&prom](Mission::Result result) { prom.set_value(result); });
×
871
    return fut.get();
×
872
}
×
873

874
void MissionImpl::clear_mission_async(const Mission::ResultCallback& callback)
×
875
{
876
    reset_mission_progress();
×
877

878
    _system_impl->mission_transfer_client().clear_items_async(
×
879
        MAV_MISSION_TYPE_MISSION,
880
        _system_impl->get_system_id(),
×
881
        [this, callback](MavlinkMissionTransferClient::Result result) {
×
882
            auto converted_result = convert_result(result);
×
883
            _system_impl->call_user_callback([callback, converted_result]() {
×
884
                if (callback) {
885
                    callback(converted_result);
886
                }
887
            });
888
        });
×
889
}
×
890

891
Mission::Result MissionImpl::set_current_mission_item(int current)
×
892
{
893
    auto prom = std::promise<Mission::Result>();
×
894
    auto fut = prom.get_future();
×
895

896
    set_current_mission_item_async(
×
897
        current, [&prom](Mission::Result result) { prom.set_value(result); });
×
898
    return fut.get();
×
899
}
×
900

901
void MissionImpl::set_current_mission_item_async(
×
902
    int current, const Mission::ResultCallback& callback)
903
{
904
    int mavlink_index = -1;
×
905
    {
906
        std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
907
        // We need to find the first mavlink item which maps to the current mission item.
908
        int i = 0;
×
909
        for (auto index : _mission_data.mavlink_mission_item_to_mission_item_indices) {
×
910
            if (index == current) {
×
911
                mavlink_index = i;
×
912
                break;
×
913
            }
914
            ++i;
×
915
        }
916
    }
×
917

918
    // If we don't have _mission_data cached from an upload or download,
919
    // we have to complain. The exception is current set to 0 because it
920
    // means to reset to the beginning.
921

922
    if (mavlink_index == -1 && current != 0) {
×
923
        _system_impl->call_user_callback([callback]() {
×
924
            if (callback) {
925
                // FIXME: come up with better error code.
926
                callback(Mission::Result::InvalidArgument);
927
                return;
928
            }
929
        });
930
    }
931

932
    _system_impl->mission_transfer_client().set_current_item_async(
×
933
        mavlink_index,
934
        _system_impl->get_system_id(),
×
935
        [this, callback](MavlinkMissionTransferClient::Result result) {
×
936
            auto converted_result = convert_result(result);
×
937
            _system_impl->call_user_callback([callback, converted_result]() {
×
938
                if (callback) {
939
                    callback(converted_result);
940
                }
941
            });
942
        });
×
943
}
×
944

945
void MissionImpl::report_progress_locked()
×
946
{
947
    if (_mission_data.mission_progress_callbacks.empty()) {
×
948
        return;
×
949
    }
950

951
    int current = current_mission_item_locked();
×
952
    int total = total_mission_items_locked();
×
953

954
    // Do not report -1 as a current mission item
955
    if (current == -1) {
×
956
        return;
×
957
    }
958

959
    bool should_report = false;
×
960
    if (_mission_data.last_current_reported_mission_item != current) {
×
961
        _mission_data.last_current_reported_mission_item = current;
×
962
        should_report = true;
×
963
    }
964
    if (_mission_data.last_total_reported_mission_item != total) {
×
965
        _mission_data.last_total_reported_mission_item = total;
×
966
        should_report = true;
×
967
    }
968

969
    if (should_report) {
×
970
        _mission_data.mission_progress_callbacks.queue(
×
971
            {current, total}, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
972
        LogDebug() << "current: " << current << ", total: " << total;
×
973
    }
974
}
975

976
std::pair<Mission::Result, bool> MissionImpl::is_mission_finished() const
×
977
{
978
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
979

980
    return is_mission_finished_locked();
×
981
}
×
982

983
std::pair<Mission::Result, bool> MissionImpl::is_mission_finished_locked() const
×
984
{
985
    if (_mission_data.last_current_mavlink_mission_item < 0) {
×
986
        return std::make_pair<Mission::Result, bool>(Mission::Result::Success, false);
×
987
    }
988

989
    if (_mission_data.last_reached_mavlink_mission_item < 0) {
×
990
        return std::make_pair<Mission::Result, bool>(Mission::Result::Success, false);
×
991
    }
992

993
    if (_mission_data.mavlink_mission_item_to_mission_item_indices.size() == 0) {
×
994
        return std::make_pair<Mission::Result, bool>(Mission::Result::Success, false);
×
995
    }
996

997
    // If mission_state is Unknown, fall back to the previous behavior
998
    if (_mission_data.mission_state == MISSION_STATE_UNKNOWN) {
×
999
        // It is not straightforward to look at "current" because it jumps to 0
1000
        // once the last item has been done. Therefore we have to lo decide using
1001
        // "reached" here.
1002
        // With PX4, it seems that we didn't use to receive a reached when RTL is initiated
1003
        // after a mission, and we needed to account for that all the way to PX4 v1.16.
1004
        const unsigned rtl_correction = _enable_return_to_launch_after_mission ? 2 : 1;
×
1005

1006
        // By accepting the current to be larger than the total, we are accepting the case
1007
        // where we no longer require the rtl_correction, as this is now getting fixed in PX4.
1008
        return std::make_pair<Mission::Result, bool>(
×
1009
            Mission::Result::Success,
×
1010
            unsigned(_mission_data.last_reached_mavlink_mission_item + rtl_correction) >=
×
1011
                _mission_data.mavlink_mission_item_to_mission_item_indices.size());
×
1012
    }
1013

1014
    // If mission_state is Completed, the mission is finished
1015
    if (_mission_data.mission_state == MISSION_STATE_COMPLETE) {
×
1016
        return std::make_pair<Mission::Result, bool>(Mission::Result::Success, true);
×
1017
    }
1018

1019
    // If mission_state is NotCompleted, the mission is not finished
1020
    return std::make_pair<Mission::Result, bool>(Mission::Result::Success, false);
×
1021
}
1022

1023
int MissionImpl::current_mission_item() const
×
1024
{
1025
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
1026
    return current_mission_item_locked();
×
1027
}
×
1028

1029
int MissionImpl::current_mission_item_locked() const
×
1030
{
1031
    // If the mission is finished, let's return the total as the current
1032
    // to signal this.
1033
    if (is_mission_finished_locked().second) {
×
1034
        return total_mission_items_locked();
×
1035
    }
1036

1037
    // We want to return the current mission item and not the underlying
1038
    // mavlink mission item.
1039
    if (_mission_data.last_current_mavlink_mission_item >=
×
1040
            static_cast<int>(_mission_data.mavlink_mission_item_to_mission_item_indices.size()) ||
×
1041
        _mission_data.last_current_mavlink_mission_item < 0) {
×
1042
        return -1;
×
1043
    }
1044

1045
    return _mission_data.mavlink_mission_item_to_mission_item_indices[static_cast<unsigned>(
×
1046
        _mission_data.last_current_mavlink_mission_item)];
×
1047
}
1048

1049
int MissionImpl::total_mission_items() const
×
1050
{
1051
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
1052
    return total_mission_items_locked();
×
1053
}
×
1054

1055
int MissionImpl::total_mission_items_locked() const
×
1056
{
1057
    if (_mission_data.mavlink_mission_item_to_mission_item_indices.size() == 0) {
×
1058
        return 0;
×
1059
    }
1060
    return _mission_data.mavlink_mission_item_to_mission_item_indices.back() + 1;
×
1061
}
1062

1063
Mission::MissionProgress MissionImpl::mission_progress()
×
1064
{
1065
    Mission::MissionProgress mission_progress;
×
1066
    mission_progress.current = current_mission_item();
×
1067
    mission_progress.total = total_mission_items();
×
1068

1069
    return mission_progress;
×
1070
}
1071

1072
Mission::MissionProgressHandle
1073
MissionImpl::subscribe_mission_progress(const Mission::MissionProgressCallback& callback)
×
1074
{
1075
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
1076
    return _mission_data.mission_progress_callbacks.subscribe(callback);
×
1077
}
×
1078

1079
void MissionImpl::unsubscribe_mission_progress(Mission::MissionProgressHandle handle)
×
1080
{
1081
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
1082
    _mission_data.mission_progress_callbacks.unsubscribe(handle);
×
1083
}
×
1084

1085
Mission::Result MissionImpl::convert_result(MavlinkMissionTransferClient::Result result)
×
1086
{
1087
    switch (result) {
×
1088
        case MavlinkMissionTransferClient::Result::Success:
×
1089
            return Mission::Result::Success;
×
1090
        case MavlinkMissionTransferClient::Result::ConnectionError:
×
1091
            return Mission::Result::Error;
×
1092
        case MavlinkMissionTransferClient::Result::Denied:
×
1093
            return Mission::Result::Denied;
×
1094
        case MavlinkMissionTransferClient::Result::TooManyMissionItems:
×
1095
            return Mission::Result::TooManyMissionItems;
×
1096
        case MavlinkMissionTransferClient::Result::Timeout:
×
1097
            return Mission::Result::Timeout;
×
1098
        case MavlinkMissionTransferClient::Result::Unsupported:
×
1099
            return Mission::Result::Unsupported;
×
1100
        case MavlinkMissionTransferClient::Result::UnsupportedFrame:
×
1101
            return Mission::Result::Unsupported;
×
1102
        case MavlinkMissionTransferClient::Result::NoMissionAvailable:
×
1103
            return Mission::Result::NoMissionAvailable;
×
1104
        case MavlinkMissionTransferClient::Result::Cancelled:
×
1105
            return Mission::Result::TransferCancelled;
×
1106
        case MavlinkMissionTransferClient::Result::MissionTypeNotConsistent:
×
1107
            return Mission::Result::Error; // should not happen
×
1108
        case MavlinkMissionTransferClient::Result::InvalidSequence:
×
1109
            return Mission::Result::Error; // should not happen
×
1110
        case MavlinkMissionTransferClient::Result::CurrentInvalid:
×
1111
            return Mission::Result::Error; // should not happen
×
1112
        case MavlinkMissionTransferClient::Result::ProtocolError:
×
1113
            return Mission::Result::ProtocolError;
×
1114
        case MavlinkMissionTransferClient::Result::InvalidParam:
×
1115
            return Mission::Result::InvalidArgument;
×
1116
        case MavlinkMissionTransferClient::Result::IntMessagesNotSupported:
×
1117
            return Mission::Result::IntMessagesNotSupported;
×
1118
        default:
×
1119
            return Mission::Result::Unknown;
×
1120
    }
1121
}
1122

1123
void MissionImpl::add_gimbal_items_v2(
×
1124
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items,
1125
    unsigned item_i,
1126
    float pitch_deg,
1127
    float yaw_deg)
1128
{
1129
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
1130

1131
    uint8_t autocontinue = 1;
×
1132

1133
    // We don't set YAW_LOCK because we probably just want to face forward.
1134
    uint32_t flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK | GIMBAL_MANAGER_FLAGS_PITCH_LOCK;
×
1135

1136
    // Pitch should be between -180 and 180 degrees
1137
    pitch_deg = fmod(pitch_deg, 360.f);
×
1138
    pitch_deg = pitch_deg > 180.f ? pitch_deg - 360.f : pitch_deg;
×
1139

1140
    // Yaw should be between -180 and 180 degrees
1141
    yaw_deg = fmod(yaw_deg, 360.f);
×
1142
    yaw_deg = yaw_deg > 180.f ? yaw_deg - 360.f : yaw_deg;
×
1143

1144
    MavlinkMissionTransferClient::ItemInt next_item{
×
1145
        static_cast<uint16_t>(int_items.size()),
×
1146
        MAV_FRAME_MISSION,
1147
        MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
1148
        current,
1149
        autocontinue,
1150
        pitch_deg, // pitch
1151
        yaw_deg, // yaw
1152
        NAN, // pitch rate
1153
        NAN, // yaw rate
1154
        static_cast<int32_t>(flags),
×
1155
        0, // reserved
1156
        0, // all devices
1157
        MAV_MISSION_TYPE_MISSION};
×
1158

1159
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
1160
    int_items.push_back(next_item);
×
1161
}
×
1162

1163
void MissionImpl::acquire_gimbal_control_v2(
×
1164
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items, unsigned item_i)
1165
{
1166
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
1167

1168
    uint8_t autocontinue = 1;
×
1169

1170
    MavlinkMissionTransferClient::ItemInt next_item{
×
1171
        static_cast<uint16_t>(int_items.size()),
×
1172
        MAV_FRAME_MISSION,
1173
        MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
1174
        current,
1175
        autocontinue,
1176
        -2.0f, // primary control sysid: set itself (autopilot) when running mission
1177
        -2.0f, // primary control compid: itself (autopilot) when running mission
1178
        -1.0f, // secondary control sysid: unchanged
1179
        -1.0f, // secondary control compid: unchanged
1180
        0, // reserved
1181
        0, // reserved
1182
        0, // all devices
1183
        MAV_MISSION_TYPE_MISSION};
×
1184

1185
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
1186
    int_items.push_back(next_item);
×
1187
}
×
1188

1189
void MissionImpl::release_gimbal_control_v2(
×
1190
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items, unsigned item_i)
1191
{
1192
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
1193

1194
    uint8_t autocontinue = 1;
×
1195

1196
    MavlinkMissionTransferClient::ItemInt next_item{
×
1197
        static_cast<uint16_t>(int_items.size()),
×
1198
        MAV_FRAME_MISSION,
1199
        MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
1200
        current,
1201
        autocontinue,
1202
        -3.0f, // primary control sysid: remove itself (autopilot) if in control
1203
        -3.0f, // primary control compid: remove itself (autopilot) if in control
1204
        -1.0f, // secondary control sysid: unchanged
1205
        -1.0f, // secondary control compid: unchanged
1206
        0, // reserved
1207
        0, // reserved
1208
        0, // all devices
1209
        MAV_MISSION_TYPE_MISSION};
×
1210

1211
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
1212
    int_items.push_back(next_item);
×
1213
}
×
1214

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