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

mavlink / MAVSDK / 11602202969

30 Oct 2024 09:50PM UTC coverage: 38.614% (+0.7%) from 37.918%
11602202969

Pull #2394

github

web-flow
Merge e66473b14 into cebb708a4
Pull Request #2394: Consolidate CI

12032 of 31160 relevant lines covered (38.61%)

246.44 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
    report_progress_locked();
×
74
}
×
75

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

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

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

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

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

107
    reset_mission_progress();
×
108

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

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

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

138
    reset_mission_progress();
×
139

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

293
    return hold_time_s;
×
294
}
295

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

309
    return acceptance_radius_m;
×
310
}
311

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

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

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

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

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

330
            uint8_t autocontinue = 1;
×
331

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

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

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

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

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

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

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

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

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

391
            uint8_t autocontinue = 1;
×
392

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

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

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

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

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

432
                uint8_t autocontinue = 1;
×
433

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

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

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

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

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

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

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

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

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

542
            uint8_t autocontinue = 1;
×
543

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

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

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

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

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

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

599
        ++item_i;
×
600
    }
601

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

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

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

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

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

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

644
    _mission_data.mavlink_mission_item_to_mission_item_indices.clear();
×
645

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

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

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

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

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

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

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

685
                have_set_position = true;
×
686

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

979
    return is_mission_finished_locked();
×
980
}
×
981

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

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

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

996
    // It is not straightforward to look at "current" because it jumps to 0
997
    // once the last item has been done. Therefore we have to lo decide using
998
    // "reached" here.
999
    // It seems that we never receive a reached when RTL is initiated after
1000
    // a mission, and we need to account for that.
1001
    const unsigned rtl_correction = _enable_return_to_launch_after_mission ? 2 : 1;
×
1002

1003
    return std::make_pair<Mission::Result, bool>(
×
1004
        Mission::Result::Success,
×
1005
        unsigned(_mission_data.last_reached_mavlink_mission_item + rtl_correction) ==
×
1006
            _mission_data.mavlink_mission_item_to_mission_item_indices.size());
×
1007
}
1008

1009
int MissionImpl::current_mission_item() const
×
1010
{
1011
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
1012
    return current_mission_item_locked();
×
1013
}
×
1014

1015
int MissionImpl::current_mission_item_locked() const
×
1016
{
1017
    // If the mission is finished, let's return the total as the current
1018
    // to signal this.
1019
    if (is_mission_finished_locked().second) {
×
1020
        return total_mission_items_locked();
×
1021
    }
1022

1023
    // We want to return the current mission item and not the underlying
1024
    // mavlink mission item.
1025
    if (_mission_data.last_current_mavlink_mission_item >=
×
1026
            static_cast<int>(_mission_data.mavlink_mission_item_to_mission_item_indices.size()) ||
×
1027
        _mission_data.last_current_mavlink_mission_item < 0) {
×
1028
        return -1;
×
1029
    }
1030

1031
    return _mission_data.mavlink_mission_item_to_mission_item_indices[static_cast<unsigned>(
×
1032
        _mission_data.last_current_mavlink_mission_item)];
×
1033
}
1034

1035
int MissionImpl::total_mission_items() const
×
1036
{
1037
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
1038
    return total_mission_items_locked();
×
1039
}
×
1040

1041
int MissionImpl::total_mission_items_locked() const
×
1042
{
1043
    if (_mission_data.mavlink_mission_item_to_mission_item_indices.size() == 0) {
×
1044
        return 0;
×
1045
    }
1046
    return _mission_data.mavlink_mission_item_to_mission_item_indices.back() + 1;
×
1047
}
1048

1049
Mission::MissionProgress MissionImpl::mission_progress()
×
1050
{
1051
    Mission::MissionProgress mission_progress;
×
1052
    mission_progress.current = current_mission_item();
×
1053
    mission_progress.total = total_mission_items();
×
1054

1055
    return mission_progress;
×
1056
}
1057

1058
Mission::MissionProgressHandle
1059
MissionImpl::subscribe_mission_progress(const Mission::MissionProgressCallback& callback)
×
1060
{
1061
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
1062
    return _mission_data.mission_progress_callbacks.subscribe(callback);
×
1063
}
×
1064

1065
void MissionImpl::unsubscribe_mission_progress(Mission::MissionProgressHandle handle)
×
1066
{
1067
    std::lock_guard<std::mutex> lock(_mission_data.mutex);
×
1068
    _mission_data.mission_progress_callbacks.unsubscribe(handle);
×
1069
}
×
1070

1071
Mission::Result MissionImpl::convert_result(MavlinkMissionTransferClient::Result result)
×
1072
{
1073
    switch (result) {
×
1074
        case MavlinkMissionTransferClient::Result::Success:
×
1075
            return Mission::Result::Success;
×
1076
        case MavlinkMissionTransferClient::Result::ConnectionError:
×
1077
            return Mission::Result::Error;
×
1078
        case MavlinkMissionTransferClient::Result::Denied:
×
1079
            return Mission::Result::Denied;
×
1080
        case MavlinkMissionTransferClient::Result::TooManyMissionItems:
×
1081
            return Mission::Result::TooManyMissionItems;
×
1082
        case MavlinkMissionTransferClient::Result::Timeout:
×
1083
            return Mission::Result::Timeout;
×
1084
        case MavlinkMissionTransferClient::Result::Unsupported:
×
1085
            return Mission::Result::Unsupported;
×
1086
        case MavlinkMissionTransferClient::Result::UnsupportedFrame:
×
1087
            return Mission::Result::Unsupported;
×
1088
        case MavlinkMissionTransferClient::Result::NoMissionAvailable:
×
1089
            return Mission::Result::NoMissionAvailable;
×
1090
        case MavlinkMissionTransferClient::Result::Cancelled:
×
1091
            return Mission::Result::TransferCancelled;
×
1092
        case MavlinkMissionTransferClient::Result::MissionTypeNotConsistent:
×
1093
            return Mission::Result::Error; // should not happen
×
1094
        case MavlinkMissionTransferClient::Result::InvalidSequence:
×
1095
            return Mission::Result::Error; // should not happen
×
1096
        case MavlinkMissionTransferClient::Result::CurrentInvalid:
×
1097
            return Mission::Result::Error; // should not happen
×
1098
        case MavlinkMissionTransferClient::Result::ProtocolError:
×
1099
            return Mission::Result::ProtocolError;
×
1100
        case MavlinkMissionTransferClient::Result::InvalidParam:
×
1101
            return Mission::Result::InvalidArgument;
×
1102
        case MavlinkMissionTransferClient::Result::IntMessagesNotSupported:
×
1103
            return Mission::Result::IntMessagesNotSupported;
×
1104
        default:
×
1105
            return Mission::Result::Unknown;
×
1106
    }
1107
}
1108

1109
void MissionImpl::add_gimbal_items_v2(
×
1110
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items,
1111
    unsigned item_i,
1112
    float pitch_deg,
1113
    float yaw_deg)
1114
{
1115
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
1116

1117
    uint8_t autocontinue = 1;
×
1118

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

1122
    // Pitch should be between -180 and 180 degrees
1123
    pitch_deg = fmod(pitch_deg, 360.f);
×
1124
    pitch_deg = pitch_deg > 180.f ? pitch_deg - 360.f : pitch_deg;
×
1125

1126
    // Yaw should be between -180 and 180 degrees
1127
    yaw_deg = fmod(yaw_deg, 360.f);
×
1128
    yaw_deg = yaw_deg > 180.f ? yaw_deg - 360.f : yaw_deg;
×
1129

1130
    MavlinkMissionTransferClient::ItemInt next_item{
×
1131
        static_cast<uint16_t>(int_items.size()),
×
1132
        MAV_FRAME_MISSION,
1133
        MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
1134
        current,
1135
        autocontinue,
1136
        pitch_deg, // pitch
1137
        yaw_deg, // yaw
1138
        NAN, // pitch rate
1139
        NAN, // yaw rate
1140
        static_cast<int32_t>(flags),
×
1141
        0, // reserved
1142
        0, // all devices
1143
        MAV_MISSION_TYPE_MISSION};
×
1144

1145
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
1146
    int_items.push_back(next_item);
×
1147
}
×
1148

1149
void MissionImpl::acquire_gimbal_control_v2(
×
1150
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items, unsigned item_i)
1151
{
1152
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
1153

1154
    uint8_t autocontinue = 1;
×
1155

1156
    MavlinkMissionTransferClient::ItemInt next_item{
×
1157
        static_cast<uint16_t>(int_items.size()),
×
1158
        MAV_FRAME_MISSION,
1159
        MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
1160
        current,
1161
        autocontinue,
1162
        -2.0f, // primary control sysid: set itself (autopilot) when running mission
1163
        -2.0f, // primary control compid: itself (autopilot) when running mission
1164
        -1.0f, // secondary control sysid: unchanged
1165
        -1.0f, // secondary control compid: unchanged
1166
        0, // reserved
1167
        0, // reserved
1168
        0, // all devices
1169
        MAV_MISSION_TYPE_MISSION};
×
1170

1171
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
1172
    int_items.push_back(next_item);
×
1173
}
×
1174

1175
void MissionImpl::release_gimbal_control_v2(
×
1176
    std::vector<MavlinkMissionTransferClient::ItemInt>& int_items, unsigned item_i)
1177
{
1178
    uint8_t current = ((int_items.size() == 0) ? 1 : 0);
×
1179

1180
    uint8_t autocontinue = 1;
×
1181

1182
    MavlinkMissionTransferClient::ItemInt next_item{
×
1183
        static_cast<uint16_t>(int_items.size()),
×
1184
        MAV_FRAME_MISSION,
1185
        MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
1186
        current,
1187
        autocontinue,
1188
        -3.0f, // primary control sysid: remove itself (autopilot) if in control
1189
        -3.0f, // primary control compid: remove itself (autopilot) if in control
1190
        -1.0f, // secondary control sysid: unchanged
1191
        -1.0f, // secondary control compid: unchanged
1192
        0, // reserved
1193
        0, // reserved
1194
        0, // all devices
1195
        MAV_MISSION_TYPE_MISSION};
×
1196

1197
    _mission_data.mavlink_mission_item_to_mission_item_indices.push_back(item_i);
×
1198
    int_items.push_back(next_item);
×
1199
}
×
1200

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

© 2025 Coveralls, Inc