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

mavlink / MAVSDK / 22148697456

18 Feb 2026 04:41PM UTC coverage: 48.984%. First build
22148697456

push

github

web-flow
Merge pull request #2770 from jazzvaz/patch-1

Fix: empty mission now return empty

1 of 2 new or added lines in 1 file covered. (50.0%)

18361 of 37484 relevant lines covered (48.98%)

670.23 hits per line

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

35.31
/cpp/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))
3✔
22
{
23
    _system_impl->register_plugin(this);
3✔
24
}
3✔
25

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

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

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

44
void MissionImpl::enable() {}
3✔
45

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

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

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

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

71
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
2✔
72
    _mission_data.last_current_mavlink_mission_item = mission_current.seq;
2✔
73
    _mission_data.mission_state = mission_current.mission_state;
2✔
74
    report_progress_locked();
2✔
75
}
2✔
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)
1✔
88
{
89
    auto prom = std::promise<Mission::Result>();
1✔
90
    auto fut = prom.get_future();
1✔
91

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

96
void MissionImpl::upload_mission_async(
3✔
97
    const Mission::MissionPlan& mission_plan, const Mission::ResultCallback& callback)
98
{
99
    if (_mission_data.last_upload.lock()) {
3✔
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();
3✔
109

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

112
    _mission_data.last_upload = _system_impl->mission_transfer_client().upload_items_async(
9✔
113
        MAV_MISSION_TYPE_MISSION,
114
        _system_impl->get_system_id(),
3✔
115
        int_items,
116
        [this, callback](MavlinkMissionTransferClient::Result result) {
6✔
117
            auto converted_result = convert_result(result);
3✔
118
            _system_impl->call_user_callback([callback, converted_result]() {
6✔
119
                if (callback) {
120
                    callback(converted_result);
121
                }
122
            });
123
        });
3✔
124
}
3✔
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
1✔
165
{
166
    auto ptr = _mission_data.last_upload.lock();
1✔
167
    if (ptr) {
1✔
168
        ptr->cancel();
1✔
169
    } else {
170
        LogWarn() << "No mission upload to cancel... ignoring";
×
171
    }
172

173
    return Mission::Result::Success;
2✔
174
}
1✔
175

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

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

188
void MissionImpl::download_mission_async(const Mission::DownloadMissionCallback& callback)
2✔
189
{
190
    if (_mission_data.last_download.lock()) {
2✔
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(
6✔
201
        MAV_MISSION_TYPE_MISSION,
202
        _system_impl->get_system_id(),
2✔
203
        [this, callback](
2✔
204
            MavlinkMissionTransferClient::Result result,
205
            std::vector<MavlinkMissionTransferClient::ItemInt> items) {
4✔
206
            auto result_and_items = convert_to_result_and_mission_items(result, items);
2✔
207
            _system_impl->call_user_callback([callback, result_and_items]() {
4✔
208
                callback(result_and_items.first, result_and_items.second);
209
            });
210
        });
4✔
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
1✔
257
{
258
    auto ptr = _mission_data.last_download.lock();
1✔
259
    if (ptr) {
1✔
260
        ptr->cancel();
1✔
261
    } else {
262
        LogWarn() << "No mission download to cancel... ignoring";
×
263
    }
264

265
    return Mission::Result::Success;
2✔
266
}
1✔
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)
2,020✔
280
{
281
    return std::isfinite(item.latitude_deg) && std::isfinite(item.longitude_deg) &&
4,040✔
282
           std::isfinite(item.relative_altitude_m);
4,040✔
283
}
284

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

294
    return hold_time_s;
2,020✔
295
}
296

297
float MissionImpl::acceptance_radius(const MissionItem& item)
2,020✔
298
{
299
    float acceptance_radius_m;
300
    if (std::isfinite(item.acceptance_radius_m)) {
2,020✔
301
        acceptance_radius_m = item.acceptance_radius_m;
20✔
302
    } else if (item.is_fly_through) {
2,000✔
303
        // _acceptance_radius_m is 0, determine the radius using fly_through
304
        acceptance_radius_m = 3.0f;
2,000✔
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;
2,020✔
311
}
312

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

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

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

324
    for (const auto& item : mission_items) {
2,023✔
325
        if (item.vehicle_action == VehicleAction::Takeoff) {
2,020✔
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)) {
2,020✔
357
                // Current is the 0th waypoint
358
                const uint8_t current = ((int_items.size() == 0) ? 1 : 0);
2,020✔
359

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

364
                MavlinkMissionTransferClient::ItemInt next_item{
2,020✔
365
                    static_cast<uint16_t>(int_items.size()),
2,020✔
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),
2,020✔
371
                    acceptance_radius(item),
2,020✔
372
                    0.0f,
373
                    item.yaw_deg,
2,020✔
374
                    x,
375
                    y,
376
                    z,
377
                    MAV_MISSION_TYPE_MISSION};
2,020✔
378

379
                last_position_valid = true; // because we checked has_valid_position
2,020✔
380

381
                _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
2,020✔
382
                int_items.push_back(next_item);
2,020✔
383
            }
384
        }
385

386
        if (std::isfinite(item.speed_m_s)) {
2,020✔
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);
2,020✔
391

392
            uint8_t autocontinue = 1;
2,020✔
393

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

409
            _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
2,020✔
410
            int_items.push_back(next_item);
2,020✔
411
        }
412

413
        if (std::isfinite(item.gimbal_yaw_deg) || std::isfinite(item.gimbal_pitch_deg)) {
2,020✔
414
            if (!_mission_data.gimbal_v2_in_control) {
2,000✔
415
                acquire_gimbal_control_v2(int_items, item_i);
2✔
416
                _mission_data.gimbal_v2_in_control = true;
2✔
417
            }
418
            add_gimbal_items_v2(int_items, item_i, item.gimbal_pitch_deg, item.gimbal_yaw_deg);
2,000✔
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) {
2,020✔
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) {
2,020✔
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 &&
2,020✔
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;
2,020✔
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;
3✔
606

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

612
    if (_enable_return_to_launch_after_mission) {
3✔
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;
3✔
632
}
633

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

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

645
    _mission_data.mavlink_mission_item_to_mission_item_indices.clear();
1✔
646

647
    if (int_items.empty()) {
1✔
NEW
648
        return result_pair;
×
649
    }
650

651
    {
652
        _enable_return_to_launch_after_mission = false;
1✔
653

654
        MissionItem new_mission_item{};
1✔
655
        bool have_set_position = false;
1✔
656

657
        for (const auto& int_item : int_items) {
41✔
658
            LogDebug() << "Assembling Message: " << int(int_item.seq);
40✔
659

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

668
                if (have_set_position) {
20✔
669
                    // When a new position comes in, create next mission item.
670
                    result_pair.second.mission_items.push_back(new_mission_item);
19✔
671
                    new_mission_item = {};
19✔
672
                    have_set_position = false;
19✔
673
                }
674

675
                new_mission_item.latitude_deg = double(int_item.x) * 1e-7;
20✔
676
                new_mission_item.longitude_deg = double(int_item.y) * 1e-7;
20✔
677
                new_mission_item.relative_altitude_m = int_item.z;
20✔
678
                new_mission_item.yaw_deg = int_item.param4;
20✔
679

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

689
                have_set_position = true;
20✔
690

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

699
                new_mission_item.gimbal_pitch_deg = int_item.param1;
×
700
                new_mission_item.gimbal_yaw_deg = int_item.param2;
×
701

702
            } else if (int_item.command == MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE) {
20✔
703
                // We need to ignore it in order to not throw an "Unsupported" error
704
                continue;
×
705

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

718
            } else if (int_item.command == MAV_CMD_IMAGE_STOP_CAPTURE) {
20✔
719
                new_mission_item.camera_action = CameraAction::StopPhotoInterval;
×
720

721
            } else if (int_item.command == MAV_CMD_VIDEO_START_CAPTURE) {
20✔
722
                new_mission_item.camera_action = CameraAction::StartVideo;
×
723

724
            } else if (int_item.command == MAV_CMD_VIDEO_STOP_CAPTURE) {
20✔
725
                new_mission_item.camera_action = CameraAction::StopVideo;
×
726

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

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

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

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

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

778
            } else if (int_item.command == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
×
779
                _enable_return_to_launch_after_mission = true;
×
780

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

787
            _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(
40✔
788
                result_pair.second.mission_items.size());
40✔
789
        }
790

791
        // Don't forget to add last mission item.
792
        result_pair.second.mission_items.push_back(new_mission_item);
1✔
793
    }
794
    return result_pair;
1✔
795
}
796

797
Mission::Result MissionImpl::start_mission()
×
798
{
799
    auto prom = std::promise<Mission::Result>();
×
800
    auto fut = prom.get_future();
×
801

802
    start_mission_async([&prom](Mission::Result result) { prom.set_value(result); });
×
803
    return fut.get();
×
804
}
×
805

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

814
Mission::Result MissionImpl::pause_mission()
×
815
{
816
    auto prom = std::promise<Mission::Result>();
×
817
    auto fut = prom.get_future();
×
818

819
    pause_mission_async([&prom](Mission::Result result) { prom.set_value(result); });
×
820
    return fut.get();
×
821
}
×
822

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

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

838
    _system_impl->call_user_callback(
×
839
        [callback, result]() { callback(command_result_to_mission_result(result)); });
840
}
841

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

868
Mission::Result MissionImpl::clear_mission()
×
869
{
870
    auto prom = std::promise<Mission::Result>();
×
871
    auto fut = prom.get_future();
×
872

873
    clear_mission_async([&prom](Mission::Result result) { prom.set_value(result); });
×
874
    return fut.get();
×
875
}
×
876

877
void MissionImpl::clear_mission_async(const Mission::ResultCallback& callback)
×
878
{
879
    reset_mission_progress();
×
880

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

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

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

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

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

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

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

948
void MissionImpl::report_progress_locked()
2✔
949
{
950
    if (_mission_data.mission_progress_callbacks.empty()) {
2✔
951
        return;
2✔
952
    }
953

954
    int current = current_mission_item_locked();
×
955
    int total = total_mission_items_locked();
×
956

957
    // Do not report -1 as a current mission item
958
    if (current == -1) {
×
959
        return;
×
960
    }
961

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

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

979
std::pair<Mission::Result, bool> MissionImpl::is_mission_finished() const
×
980
{
981
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
982

983
    return is_mission_finished_locked();
×
984
}
×
985

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

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

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

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

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

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

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

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

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

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

1048
    return _mission_data.mavlink_mission_item_to_mission_item_indices[static_cast<unsigned>(
×
1049
        _mission_data.last_current_mavlink_mission_item)];
×
1050
}
1051

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

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

1066
Mission::MissionProgress MissionImpl::mission_progress()
×
1067
{
1068
    Mission::MissionProgress mission_progress;
×
1069
    mission_progress.current = current_mission_item();
×
1070
    mission_progress.total = total_mission_items();
×
1071

1072
    return mission_progress;
×
1073
}
1074

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

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

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

1126
void MissionImpl::add_gimbal_items_v2(
2,000✔
1127
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items,
1128
    unsigned item_i,
1129
    float pitch_deg,
1130
    float yaw_deg)
1131
{
1132
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
2,000✔
1133

1134
    uint8_t autocontinue = 1;
2,000✔
1135

1136
    // We don't set YAW_LOCK because we probably just want to face forward.
1137
    uint32_t flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK | GIMBAL_MANAGER_FLAGS_PITCH_LOCK;
2,000✔
1138

1139
    // Pitch should be between -180 and 180 degrees
1140
    pitch_deg = fmod(pitch_deg, 360.f);
2,000✔
1141
    pitch_deg = pitch_deg > 180.f ? pitch_deg - 360.f : pitch_deg;
2,000✔
1142

1143
    // Yaw should be between -180 and 180 degrees
1144
    yaw_deg = fmod(yaw_deg, 360.f);
2,000✔
1145
    yaw_deg = yaw_deg > 180.f ? yaw_deg - 360.f : yaw_deg;
2,000✔
1146

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

1162
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
2,000✔
1163
    int_items.push_back(next_item);
2,000✔
1164
}
2,000✔
1165

1166
void MissionImpl::acquire_gimbal_control_v2(
2✔
1167
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items, unsigned item_i)
1168
{
1169
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
2✔
1170

1171
    uint8_t autocontinue = 1;
2✔
1172

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

1188
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
2✔
1189
    int_items.push_back(next_item);
2✔
1190
}
2✔
1191

1192
void MissionImpl::release_gimbal_control_v2(
2✔
1193
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items, unsigned item_i)
1194
{
1195
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
2✔
1196

1197
    uint8_t autocontinue = 1;
2✔
1198

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

1214
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
2✔
1215
    int_items.push_back(next_item);
2✔
1216
}
2✔
1217

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