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

mavlink / MAVSDK / 20215172078

14 Dec 2025 10:34PM UTC coverage: 47.959% (-0.06%) from 48.021%
20215172078

push

github

web-flow
Merge pull request #2738 from mavlink/pr-set-gps-origin

Add method set to GPS origin

0 of 36 new or added lines in 2 files covered. (0.0%)

12 existing lines in 6 files now uncovered.

17659 of 36821 relevant lines covered (47.96%)

465.45 hits per line

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

13.93
/src/mavsdk/plugins/action/action_impl.cpp
1
#include "action_impl.h"
2
#include "mavsdk_impl.h"
3
#include "math_utils.h"
4
#include "flight_mode.h"
5
#include "px4_custom_mode.h"
6
#include <cmath>
7
#include <future>
8

9
namespace mavsdk {
10

11
ActionImpl::ActionImpl(System& system) : PluginImplBase(system)
×
12
{
13
    _system_impl->register_plugin(this);
×
14
}
×
15

16
ActionImpl::ActionImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
1✔
17
{
18
    _system_impl->register_plugin(this);
1✔
19
}
1✔
20

21
ActionImpl::~ActionImpl()
2✔
22
{
23
    _system_impl->unregister_plugin(this);
1✔
24
}
2✔
25

26
void ActionImpl::init()
1✔
27
{
28
    // We need the system state.
29
    _system_impl->register_mavlink_message_handler(
1✔
30
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
31
        [this](const mavlink_message_t& message) { process_extended_sys_state(message); },
×
32
        this);
33
}
1✔
34

35
void ActionImpl::deinit()
1✔
36
{
37
    _system_impl->unregister_all_mavlink_message_handlers_blocking(this);
1✔
38
}
1✔
39

40
void ActionImpl::enable()
1✔
41
{
42
    // And we need to make sure the system state is actually sent.
43
    // We use the async call here because we should not block in the init call because
44
    // we won't receive an answer anyway in init because the receive loop is not
45
    // called while we are being created here.
46
    _system_impl->set_msg_rate_async(
1✔
47
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
48
        1.0,
49
        nullptr,
50
        MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT);
51
}
1✔
52

53
void ActionImpl::disable() {}
1✔
54

55
Action::Result ActionImpl::arm() const
2✔
56
{
57
    auto prom = std::promise<Action::Result>();
2✔
58
    auto fut = prom.get_future();
2✔
59

60
    arm_async([&prom](Action::Result result) { prom.set_value(result); });
4✔
61

62
    return fut.get();
2✔
63
}
2✔
64

65
Action::Result ActionImpl::arm_force() const
×
66
{
67
    auto prom = std::promise<Action::Result>();
×
68
    auto fut = prom.get_future();
×
69

70
    arm_force_async([&prom](Action::Result result) { prom.set_value(result); });
×
71

72
    return fut.get();
×
73
}
×
74

75
Action::Result ActionImpl::disarm() const
2✔
76
{
77
    auto prom = std::promise<Action::Result>();
2✔
78
    auto fut = prom.get_future();
2✔
79

80
    disarm_async([&prom](Action::Result result) { prom.set_value(result); });
4✔
81

82
    return fut.get();
2✔
83
}
2✔
84

85
Action::Result ActionImpl::terminate() const
×
86
{
87
    auto prom = std::promise<Action::Result>();
×
88
    auto fut = prom.get_future();
×
89

90
    terminate_async([&prom](Action::Result result) { prom.set_value(result); });
×
91

92
    return fut.get();
×
93
}
×
94

95
Action::Result ActionImpl::kill() const
×
96
{
97
    auto prom = std::promise<Action::Result>();
×
98
    auto fut = prom.get_future();
×
99

100
    kill_async([&prom](Action::Result result) { prom.set_value(result); });
×
101

102
    return fut.get();
×
103
}
×
104

105
Action::Result ActionImpl::reboot() const
×
106
{
107
    auto prom = std::promise<Action::Result>();
×
108
    auto fut = prom.get_future();
×
109

110
    reboot_async([&prom](Action::Result result) { prom.set_value(result); });
×
111

112
    return fut.get();
×
113
}
×
114

115
Action::Result ActionImpl::shutdown() const
×
116
{
117
    auto prom = std::promise<Action::Result>();
×
118
    auto fut = prom.get_future();
×
119

120
    shutdown_async([&prom](Action::Result result) { prom.set_value(result); });
×
121

122
    return fut.get();
×
123
}
×
124

125
Action::Result ActionImpl::takeoff() const
×
126
{
127
    auto prom = std::promise<Action::Result>();
×
128
    auto fut = prom.get_future();
×
129

130
    takeoff_async([&prom](Action::Result result) { prom.set_value(result); });
×
131

132
    return fut.get();
×
133
}
×
134

135
Action::Result ActionImpl::land() const
×
136
{
137
    auto prom = std::promise<Action::Result>();
×
138
    auto fut = prom.get_future();
×
139

140
    land_async([&prom](Action::Result result) { prom.set_value(result); });
×
141

142
    return fut.get();
×
143
}
×
144

145
Action::Result ActionImpl::return_to_launch() const
×
146
{
147
    auto prom = std::promise<Action::Result>();
×
148
    auto fut = prom.get_future();
×
149

150
    return_to_launch_async([&prom](Action::Result result) { prom.set_value(result); });
×
151

152
    return fut.get();
×
153
}
×
154

155
Action::Result ActionImpl::goto_location(
×
156
    const double latitude_deg,
157
    const double longitude_deg,
158
    const float altitude_amsl_m,
159
    const float yaw_deg)
160
{
161
    auto prom = std::promise<Action::Result>();
×
162
    auto fut = prom.get_future();
×
163

164
    goto_location_async(
×
165
        latitude_deg, longitude_deg, altitude_amsl_m, yaw_deg, [&prom](Action::Result result) {
×
166
            prom.set_value(result);
×
167
        });
×
168

169
    return fut.get();
×
170
}
×
171

172
Action::Result ActionImpl::do_orbit(
×
173
    const float radius_m,
174
    const float velocity_ms,
175
    const Action::OrbitYawBehavior yaw_behavior,
176
    const double latitude_deg,
177
    const double longitude_deg,
178
    const double absolute_altitude_m)
179
{
180
    auto prom = std::promise<Action::Result>();
×
181
    auto fut = prom.get_future();
×
182

183
    do_orbit_async(
×
184
        radius_m,
185
        velocity_ms,
186
        yaw_behavior,
187
        latitude_deg,
188
        longitude_deg,
189
        absolute_altitude_m,
190
        [&prom](Action::Result result) { prom.set_value(result); });
×
191

192
    return fut.get();
×
193
}
×
194

195
Action::Result ActionImpl::hold() const
×
196
{
197
    auto prom = std::promise<Action::Result>();
×
198
    auto fut = prom.get_future();
×
199

200
    hold_async([&prom](Action::Result result) { prom.set_value(result); });
×
201

202
    return fut.get();
×
203
}
×
204

205
Action::Result ActionImpl::set_actuator(const int index, const float value)
×
206
{
207
    auto prom = std::promise<Action::Result>();
×
208
    auto fut = prom.get_future();
×
209

210
    set_actuator_async(index, value, [&prom](Action::Result result) { prom.set_value(result); });
×
211

212
    return fut.get();
×
213
}
×
214

215
Action::Result ActionImpl::transition_to_fixedwing() const
×
216
{
217
    auto prom = std::promise<Action::Result>();
×
218
    auto fut = prom.get_future();
×
219

220
    transition_to_fixedwing_async([&prom](Action::Result result) { prom.set_value(result); });
×
221

222
    return fut.get();
×
223
}
×
224

225
Action::Result ActionImpl::transition_to_multicopter() const
×
226
{
227
    auto prom = std::promise<Action::Result>();
×
228
    auto fut = prom.get_future();
×
229

230
    transition_to_multicopter_async([&prom](Action::Result result) { prom.set_value(result); });
×
231

232
    return fut.get();
×
233
}
×
234

235
void ActionImpl::arm_async(const Action::ResultCallback& callback) const
2✔
236
{
237
    auto send_arm_command = [this, callback]() {
8✔
238
        MavlinkCommandSender::CommandLong command{};
2✔
239

240
        command.command = MAV_CMD_COMPONENT_ARM_DISARM;
2✔
241
        command.params.maybe_param1 = 1.0f; // arm
2✔
242
        command.target_component_id = _system_impl->get_autopilot_id();
2✔
243

244
        _system_impl->send_command_async(
4✔
245
            command, [this, callback](MavlinkCommandSender::Result result, float) {
2✔
246
                command_result_callback(result, callback);
2✔
247
            });
2✔
248
    };
2✔
249

250
    if (need_hold_before_arm()) {
2✔
251
        _system_impl->set_flight_mode_async(
×
252
            FlightMode::Hold,
253
            [callback, send_arm_command](MavlinkCommandSender::Result result, float) {
×
254
                Action::Result action_result = action_result_from_command_result(result);
×
255
                if (action_result != Action::Result::Success) {
×
256
                    if (callback) {
×
257
                        callback(action_result);
×
258
                    }
259
                }
260
                send_arm_command();
×
261
            });
×
262
        return;
×
263
    } else {
264
        send_arm_command();
2✔
265
    }
266
}
2✔
267

268
bool ActionImpl::need_hold_before_arm() const
2✔
269
{
270
    if (_system_impl->autopilot() == Autopilot::Px4) {
2✔
271
        return need_hold_before_arm_px4();
×
272
    } else {
273
        return need_hold_before_arm_apm();
2✔
274
    }
275
}
276

277
bool ActionImpl::need_hold_before_arm_px4() const
×
278
{
279
    if (_system_impl->get_flight_mode() == FlightMode::Mission ||
×
280
        _system_impl->get_flight_mode() == FlightMode::ReturnToLaunch) {
×
281
        return true;
×
282
    } else {
283
        return false;
×
284
    }
285
}
286

287
bool ActionImpl::need_hold_before_arm_apm() const
2✔
288
{
289
    if (_system_impl->get_flight_mode() == FlightMode::Mission ||
4✔
290
        _system_impl->get_flight_mode() == FlightMode::ReturnToLaunch ||
4✔
291
        _system_impl->get_flight_mode() == FlightMode::Land) {
2✔
292
        return true;
×
293
    } else {
294
        return false;
2✔
295
    }
296
}
297

298
void ActionImpl::arm_force_async(const Action::ResultCallback& callback) const
×
299
{
300
    MavlinkCommandSender::CommandLong command{};
×
301

302
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
×
303
    command.params.maybe_param1 = 0.0f; // arm
×
304
    command.params.maybe_param2 = 21196.f; // magic number to force
×
305
    command.target_component_id = _system_impl->get_autopilot_id();
×
306

307
    _system_impl->send_command_async(
×
308
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
309
            command_result_callback(result, callback);
×
310
        });
×
311
}
×
312

313
void ActionImpl::disarm_async(const Action::ResultCallback& callback) const
2✔
314
{
315
    MavlinkCommandSender::CommandLong command{};
2✔
316

317
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
2✔
318
    command.params.maybe_param1 = 0.0f; // disarm
2✔
319
    command.target_component_id = _system_impl->get_autopilot_id();
2✔
320

321
    _system_impl->send_command_async(
2✔
322
        command, [this, callback](MavlinkCommandSender::Result result, float) {
2✔
323
            command_result_callback(result, callback);
2✔
324
        });
2✔
325
}
2✔
326

327
void ActionImpl::terminate_async(const Action::ResultCallback& callback) const
×
328
{
329
    MavlinkCommandSender::CommandLong command{};
×
330

331
    command.command = MAV_CMD_DO_FLIGHTTERMINATION;
×
332
    command.params.maybe_param1 = 1.0f;
×
333
    command.target_component_id = _system_impl->get_autopilot_id();
×
334

335
    _system_impl->send_command_async(
×
336
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
337
            command_result_callback(result, callback);
×
338
        });
×
339
}
×
340

341
void ActionImpl::kill_async(const Action::ResultCallback& callback) const
×
342
{
343
    MavlinkCommandSender::CommandLong command{};
×
344

345
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
×
346
    command.params.maybe_param1 = 0.0f; // kill
×
347
    command.params.maybe_param2 = 21196.f; // magic number to enforce in-air
×
348
    command.target_component_id = _system_impl->get_autopilot_id();
×
349

350
    _system_impl->send_command_async(
×
351
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
352
            command_result_callback(result, callback);
×
353
        });
×
354
}
×
355

356
void ActionImpl::reboot_async(const Action::ResultCallback& callback) const
×
357
{
358
    MavlinkCommandSender::CommandLong command{};
×
359

360
    command.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
×
361
    command.params.maybe_param1 = 1.0f; // reboot autopilot
×
362
    command.target_component_id = _system_impl->get_autopilot_id();
×
363

364
    _system_impl->send_command_async(
×
365
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
366
            command_result_callback(result, callback);
×
367
        });
×
368
}
×
369

370
void ActionImpl::shutdown_async(const Action::ResultCallback& callback) const
×
371
{
372
    MavlinkCommandSender::CommandLong command{};
×
373

374
    command.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
×
375
    command.params.maybe_param1 = 2.0f; // shutdown autopilot
×
376
    command.target_component_id = _system_impl->get_autopilot_id();
×
377

378
    _system_impl->send_command_async(
×
379
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
380
            command_result_callback(result, callback);
×
381
        });
×
382
}
×
383

384
void ActionImpl::takeoff_async(const Action::ResultCallback& callback) const
×
385
{
386
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
387
        takeoff_async_px4(callback);
×
388
    } else {
389
        takeoff_async_apm(callback);
×
390
    }
391
}
×
392

393
void ActionImpl::takeoff_async_px4(const Action::ResultCallback& callback) const
×
394
{
395
    MavlinkCommandSender::CommandLong command{};
×
396

397
    command.command = MAV_CMD_NAV_TAKEOFF;
×
398
    command.target_component_id = _system_impl->get_autopilot_id();
×
399

400
    _system_impl->send_command_async(
×
401
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
402
            command_result_callback(result, callback);
×
403
        });
×
404
}
×
405

406
void ActionImpl::takeoff_async_apm(const Action::ResultCallback& callback) const
×
407
{
408
    auto send_takeoff_command = [this, callback]() {
×
409
        MavlinkCommandSender::CommandLong command{};
×
410

411
        command.command = MAV_CMD_NAV_TAKEOFF;
×
412
        command.target_component_id = _system_impl->get_autopilot_id();
×
413
        command.params.maybe_param7 = get_takeoff_altitude().second;
×
414

415
        _system_impl->send_command_async(
×
416
            command, [this, callback](MavlinkCommandSender::Result result, float) {
×
417
                command_result_callback(result, callback);
×
418
            });
×
419
    };
×
420
    if (_system_impl->get_flight_mode() != FlightMode::Offboard) {
×
421
        _system_impl->set_flight_mode_async(
×
422
            FlightMode::Offboard,
423
            [callback, send_takeoff_command](MavlinkCommandSender::Result result, float) {
×
424
                Action::Result action_result = action_result_from_command_result(result);
×
425
                if (action_result != Action::Result::Success) {
×
426
                    if (callback) {
×
427
                        callback(action_result);
×
428
                    }
429
                } else {
430
                    send_takeoff_command();
×
431
                }
432
            });
×
433
    } else {
434
        send_takeoff_command();
×
435
    }
436
}
×
437

438
void ActionImpl::land_async(const Action::ResultCallback& callback) const
×
439
{
440
    MavlinkCommandSender::CommandLong command{};
×
441

442
    command.command = MAV_CMD_NAV_LAND;
×
443
    command.params.maybe_param4 = NAN; // Don't change yaw.
×
444
    command.target_component_id = _system_impl->get_autopilot_id();
×
445

446
    _system_impl->send_command_async(
×
447
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
448
            command_result_callback(result, callback);
×
449
        });
×
450
}
×
451

452
void ActionImpl::return_to_launch_async(const Action::ResultCallback& callback) const
×
453
{
454
    _system_impl->set_flight_mode_async(
×
455
        FlightMode::ReturnToLaunch, [this, callback](MavlinkCommandSender::Result result, float) {
×
456
            command_result_callback(result, callback);
×
457
        });
×
458
}
×
459

460
void ActionImpl::goto_location_async(
×
461
    const double latitude_deg,
462
    const double longitude_deg,
463
    const float altitude_amsl_m,
464
    const float yaw_deg,
465
    const Action::ResultCallback& callback)
466
{
467
    auto send_do_reposition =
468
        [this, callback, yaw_deg, latitude_deg, longitude_deg, altitude_amsl_m]() {
×
469
            MavlinkCommandSender::CommandInt command{};
×
470

471
            command.command = MAV_CMD_DO_REPOSITION;
×
472
            command.target_component_id = _system_impl->get_autopilot_id();
×
473
            command.frame = MAV_FRAME_GLOBAL_INT;
×
474
            command.params.maybe_param4 = static_cast<float>(to_rad_from_deg(yaw_deg));
×
475
            command.params.x = int32_t(std::round(latitude_deg * 1e7));
×
476
            command.params.y = int32_t(std::round(longitude_deg * 1e7));
×
477
            command.params.maybe_z = altitude_amsl_m;
×
478
            command.params.maybe_param2 = static_cast<float>(MAV_DO_REPOSITION_FLAGS_CHANGE_MODE);
×
479

480
            _system_impl->send_command_async(
×
481
                command, [this, callback](MavlinkCommandSender::Result result, float) {
×
482
                    command_result_callback(result, callback);
×
483
                });
×
484
        };
×
485
    FlightMode goto_flight_mode;
486
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
487
        goto_flight_mode = FlightMode::Hold;
×
488
    } else {
489
        goto_flight_mode = FlightMode::Offboard;
×
490
    }
491
    if (_system_impl->get_flight_mode() != goto_flight_mode) {
×
492
        _system_impl->set_flight_mode_async(
×
493
            goto_flight_mode,
494
            [this, callback, send_do_reposition](MavlinkCommandSender::Result result, float) {
×
495
                Action::Result action_result = action_result_from_command_result(result);
×
496
                if (action_result != Action::Result::Success) {
×
497
                    command_result_callback(result, callback);
×
498
                    return;
×
499
                }
500
                send_do_reposition();
×
501
            });
502
        return;
×
503
    }
504

505
    send_do_reposition();
×
506
}
×
507

508
void ActionImpl::do_orbit_async(
×
509
    const float radius_m,
510
    const float velocity_ms,
511
    const Action::OrbitYawBehavior yaw_behavior,
512
    const double latitude_deg,
513
    const double longitude_deg,
514
    const double absolute_altitude_m,
515
    const Action::ResultCallback& callback)
516
{
517
    MavlinkCommandSender::CommandInt command{};
×
518

519
    command.command = MAV_CMD_DO_ORBIT;
×
520
    command.target_component_id = _system_impl->get_autopilot_id();
×
521
    command.params.maybe_param1 = radius_m;
×
522
    command.params.maybe_param2 = velocity_ms;
×
523
    command.params.maybe_param3 = static_cast<float>(yaw_behavior);
×
524
    command.params.x = int32_t(std::round(latitude_deg * 1e7));
×
525
    command.params.y = int32_t(std::round(longitude_deg * 1e7));
×
526
    command.params.maybe_z = static_cast<float>(absolute_altitude_m);
×
527

528
    _system_impl->send_command_async(
×
529
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
530
            command_result_callback(result, callback);
×
531
        });
×
532
}
×
533

534
void ActionImpl::hold_async(const Action::ResultCallback& callback) const
×
535
{
536
    _system_impl->set_flight_mode_async(
×
537
        FlightMode::Hold, [this, callback](MavlinkCommandSender::Result result, float) {
×
538
            command_result_callback(result, callback);
×
539
        });
×
540
}
×
541

542
void ActionImpl::set_actuator_async(
×
543
    const int index, const float value, const Action::ResultCallback& callback)
544
{
545
    MavlinkCommandSender::CommandLong command{};
×
546
    command.target_component_id = _system_impl->get_autopilot_id();
×
547

548
    if (_system_impl->autopilot() == Autopilot::ArduPilot) {
×
549
        command.command = MAV_CMD_DO_SET_SERVO;
×
550
        command.params.maybe_param1 = static_cast<float>(index);
×
551
        command.params.maybe_param2 = value;
×
552
    } else {
553
        auto zero_based_index = index - 1;
×
554
        if (zero_based_index >= 0) {
×
555
            command.command = MAV_CMD_DO_SET_ACTUATOR;
×
556
            switch (zero_based_index % 6) {
×
557
                case 0:
×
558
                    command.params.maybe_param1 = value;
×
559
                    break;
×
560
                case 1:
×
561
                    command.params.maybe_param2 = value;
×
562
                    break;
×
563
                case 2:
×
564
                    command.params.maybe_param3 = value;
×
565
                    break;
×
566
                case 3:
×
567
                    command.params.maybe_param4 = value;
×
568
                    break;
×
569
                case 4:
×
570
                    command.params.maybe_param5 = value;
×
571
                    break;
×
572
                case 5:
×
573
                    command.params.maybe_param6 = value;
×
574
                    break;
×
575
            }
576
            command.params.maybe_param7 = static_cast<float>(zero_based_index / 6);
×
577
        } else {
578
            if (callback) {
×
579
                _system_impl->call_user_callback([temp_callback = callback]() {
×
580
                    temp_callback(Action::Result::InvalidArgument);
581
                });
582
            }
583
            return;
×
584
        }
585
    }
586

587
    _system_impl->send_command_async(
×
588
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
589
            command_result_callback(result, callback);
×
590
        });
×
591
}
592

593
void ActionImpl::transition_to_fixedwing_async(const Action::ResultCallback& callback) const
×
594
{
595
    if (!_vtol_transition_support_known) {
×
596
        if (callback) {
×
597
            callback(Action::Result::VtolTransitionSupportUnknown);
×
598
        }
599
        return;
×
600
    }
601

602
    if (!_vtol_transition_possible) {
×
603
        if (callback) {
×
604
            callback(Action::Result::NoVtolTransitionSupport);
×
605
        }
606
        return;
×
607
    }
608

609
    MavlinkCommandSender::CommandLong command{};
×
610

611
    command.command = MAV_CMD_DO_VTOL_TRANSITION;
×
612
    command.params.maybe_param1 = static_cast<float>(MAV_VTOL_STATE_FW);
×
613
    command.target_component_id = _system_impl->get_autopilot_id();
×
614

615
    _system_impl->send_command_async(
×
616
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
617
            command_result_callback(result, callback);
×
618
        });
×
619
}
620

621
void ActionImpl::transition_to_multicopter_async(const Action::ResultCallback& callback) const
×
622
{
623
    if (!_vtol_transition_support_known) {
×
624
        if (callback) {
×
625
            callback(Action::Result::VtolTransitionSupportUnknown);
×
626
        }
627
        return;
×
628
    }
629

630
    if (!_vtol_transition_possible) {
×
631
        if (callback) {
×
632
            callback(Action::Result::NoVtolTransitionSupport);
×
633
        }
634
        return;
×
635
    }
636
    MavlinkCommandSender::CommandLong command{};
×
637

638
    command.command = MAV_CMD_DO_VTOL_TRANSITION;
×
639
    command.params.maybe_param1 = static_cast<float>(MAV_VTOL_STATE_MC);
×
640
    command.target_component_id = _system_impl->get_autopilot_id();
×
641

642
    _system_impl->send_command_async(
×
643
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
644
            command_result_callback(result, callback);
×
645
        });
×
646
}
647

648
void ActionImpl::process_extended_sys_state(const mavlink_message_t& message)
×
649
{
650
    mavlink_extended_sys_state_t extended_sys_state;
651
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
652

653
    if (extended_sys_state.vtol_state != MAV_VTOL_STATE_UNDEFINED) {
×
654
        _vtol_transition_possible = true;
×
655
    } else {
656
        _vtol_transition_possible = false;
×
657
    }
658
    _vtol_transition_support_known = true;
×
659
}
×
660

661
void ActionImpl::set_takeoff_altitude_async(
×
662
    const float relative_altitude_m, const Action::ResultCallback& callback)
663
{
664
    callback(set_takeoff_altitude(relative_altitude_m));
×
665
}
×
666

667
Action::Result ActionImpl::set_takeoff_altitude(float relative_altitude_m)
×
668
{
669
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
670
        return set_takeoff_altitude_px4(relative_altitude_m);
×
671
    } else {
672
        return set_takeoff_altitude_apm(relative_altitude_m);
×
673
    }
674
}
675

676
Action::Result ActionImpl::set_takeoff_altitude_px4(float relative_altitude_m)
×
677
{
678
    _takeoff_altitude = relative_altitude_m;
×
679

680
    const MavlinkParameterClient::Result result =
681
        _system_impl->set_param_float(TAKEOFF_ALT_PARAM, relative_altitude_m);
×
682
    return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
683
                                                                 Action::Result::ParameterError;
×
684
}
685

686
Action::Result ActionImpl::set_takeoff_altitude_apm(float relative_altitude_m)
×
687
{
688
    _takeoff_altitude = relative_altitude_m;
×
689
    return Action::Result::Success;
×
690
}
691

692
void ActionImpl::get_takeoff_altitude_async(
×
693
    const Action::GetTakeoffAltitudeCallback& callback) const
694
{
695
    auto altitude_result = get_takeoff_altitude();
×
696
    callback(altitude_result.first, altitude_result.second);
×
697
}
×
698

699
std::pair<Action::Result, float> ActionImpl::get_takeoff_altitude() const
×
700
{
701
    if (_system_impl->autopilot() == Autopilot::ArduPilot) {
×
702
        return std::make_pair<>(Action::Result::Success, _takeoff_altitude);
×
703
    } else {
704
        auto result = _system_impl->get_param_float(TAKEOFF_ALT_PARAM);
×
705
        return std::make_pair<>(
×
706
            (result.first == MavlinkParameterClient::Result::Success) ?
×
707
                Action::Result::Success :
708
                Action::Result::ParameterError,
709
            result.second);
×
710
    }
711
}
712

713
void ActionImpl::set_return_to_launch_altitude_async(
×
714
    const float relative_altitude_m, const Action::ResultCallback& callback) const
715
{
716
    callback(set_return_to_launch_altitude(relative_altitude_m));
×
717
}
×
718

719
Action::Result ActionImpl::set_return_to_launch_altitude(const float relative_altitude_m) const
×
720
{
721
    const MavlinkParameterClient::Result result =
722
        _system_impl->set_param_float(RTL_RETURN_ALTITUDE_PARAM, relative_altitude_m);
×
723
    return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
724
                                                                 Action::Result::ParameterError;
×
725
}
726

727
void ActionImpl::get_return_to_launch_altitude_async(
×
728
    const Action::GetReturnToLaunchAltitudeCallback& callback) const
729
{
730
    const auto get_result = get_return_to_launch_altitude();
×
731
    callback(get_result.first, get_result.second);
×
732
}
×
733

734
std::pair<Action::Result, float> ActionImpl::get_return_to_launch_altitude() const
×
735
{
736
    auto result = _system_impl->get_param_float(RTL_RETURN_ALTITUDE_PARAM);
×
737
    return std::make_pair<>(
×
738
        (result.first == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
739
                                                                    Action::Result::ParameterError,
740
        result.second);
×
741
}
742

743
void ActionImpl::set_current_speed_async(float speed_m_s, const Action::ResultCallback& callback)
×
744
{
745
    MavlinkCommandSender::CommandLong command{};
×
746

747
    command.command = MAV_CMD_DO_CHANGE_SPEED;
×
748
    command.params.maybe_param1 = 1.0f; // ground speed
×
749
    command.params.maybe_param2 = speed_m_s;
×
750
    command.params.maybe_param3 = -1.0f; // no throttle set
×
751
    command.params.maybe_param4 = 0.0f; // reserved
×
752
    command.target_component_id = _system_impl->get_autopilot_id();
×
753

754
    _system_impl->send_command_async(
×
755
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
756
            command_result_callback(result, callback);
×
757
        });
×
758
}
×
759

760
Action::Result ActionImpl::set_current_speed(float speed_m_s)
×
761
{
762
    auto prom = std::promise<Action::Result>();
×
763
    auto fut = prom.get_future();
×
764

765
    set_current_speed_async(speed_m_s, [&prom](Action::Result result) { prom.set_value(result); });
×
766

767
    return fut.get();
×
768
}
×
769

NEW
770
Action::Result ActionImpl::set_gps_global_origin(
×
771
    double latitude_deg, double longitude_deg, float absolute_altitude_m) const
772
{
NEW
773
    const int32_t latitude_e7 = static_cast<int32_t>(std::round(latitude_deg * 1e7));
×
NEW
774
    const int32_t longitude_e7 = static_cast<int32_t>(std::round(longitude_deg * 1e7));
×
NEW
775
    const int32_t altitude_mm = static_cast<int32_t>(std::round(absolute_altitude_m * 1000.0f));
×
776

NEW
777
    auto prom = std::promise<Action::Result>();
×
NEW
778
    auto fut = prom.get_future();
×
NEW
779
    std::atomic<bool> prom_already_set{false};
×
780

781
    // Use a unique cookie for this handler
NEW
782
    const void* cookie = this;
×
783

784
    // Register handler for GPS_GLOBAL_ORIGIN response.
785
    // Note: Older PX4 versions (pre-v1.17) had a race condition where they would
786
    // broadcast GPS_GLOBAL_ORIGIN with stale values immediately after receiving
787
    // SET_GPS_GLOBAL_ORIGIN, before EKF2 had processed the command. To handle
788
    // this, we wait for a response with matching values rather than accepting
789
    // the first response.
NEW
790
    _system_impl->register_mavlink_message_handler(
×
791
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
NEW
792
        [&prom, &prom_already_set, latitude_e7, longitude_e7, altitude_mm](
×
NEW
793
            const mavlink_message_t& message) {
×
794
            mavlink_gps_global_origin_t origin;
NEW
795
            mavlink_msg_gps_global_origin_decode(&message, &origin);
×
796

797
            // Only signal success when we receive the values we set
NEW
798
            if (origin.latitude == latitude_e7 && origin.longitude == longitude_e7 &&
×
NEW
799
                origin.altitude == altitude_mm) {
×
NEW
800
                if (!prom_already_set.exchange(true)) {
×
NEW
801
                    prom.set_value(Action::Result::Success);
×
802
                }
803
            }
804
            // Otherwise, keep waiting for the correct values (or timeout)
NEW
805
        },
×
806
        cookie);
807

808
    // Send the SET_GPS_GLOBAL_ORIGIN message
NEW
809
    if (!_system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
810
            mavlink_message_t message;
NEW
811
            mavlink_msg_set_gps_global_origin_pack_chan(
×
NEW
812
                mavlink_address.system_id,
×
NEW
813
                mavlink_address.component_id,
×
814
                channel,
815
                &message,
NEW
816
                _system_impl->get_system_id(),
×
NEW
817
                latitude_e7,
×
NEW
818
                longitude_e7,
×
NEW
819
                altitude_mm,
×
820
                0);
NEW
821
            return message;
×
822
        })) {
NEW
823
        _system_impl->unregister_mavlink_message_handler(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, cookie);
×
NEW
824
        return Action::Result::ConnectionError;
×
825
    }
826

827
    // Wait for response with timeout
NEW
828
    auto status = fut.wait_for(std::chrono::duration<double>(_system_impl->timeout_s()));
×
829

NEW
830
    _system_impl->unregister_mavlink_message_handler(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, cookie);
×
831

NEW
832
    if (status == std::future_status::timeout) {
×
NEW
833
        return Action::Result::Timeout;
×
834
    }
835

NEW
836
    return fut.get();
×
NEW
837
}
×
838

839
Action::Result ActionImpl::action_result_from_command_result(MavlinkCommandSender::Result result)
4✔
840
{
841
    switch (result) {
4✔
842
        case MavlinkCommandSender::Result::Success:
2✔
843
            return Action::Result::Success;
2✔
844
        case MavlinkCommandSender::Result::NoSystem:
×
845
            return Action::Result::NoSystem;
×
846
        case MavlinkCommandSender::Result::ConnectionError:
×
847
            return Action::Result::ConnectionError;
×
848
        case MavlinkCommandSender::Result::Busy:
×
849
            return Action::Result::Busy;
×
850
        case MavlinkCommandSender::Result::Denied:
2✔
851
            // Fallthrough
852
        case MavlinkCommandSender::Result::TemporarilyRejected:
853
            return Action::Result::CommandDenied;
2✔
854
        case MavlinkCommandSender::Result::Failed:
×
855
            return Action::Result::Failed;
×
856
        case MavlinkCommandSender::Result::Timeout:
×
857
            return Action::Result::Timeout;
×
858
        case MavlinkCommandSender::Result::Unsupported:
×
859
            return Action::Result::Unsupported;
×
860
        default:
×
861
            return Action::Result::Unknown;
×
862
    }
863
}
864

865
void ActionImpl::command_result_callback(
4✔
866
    MavlinkCommandSender::Result command_result, const Action::ResultCallback& callback) const
867
{
868
    if (command_result == MavlinkCommandSender::Result::InProgress) {
4✔
869
        // We only want to return once, so we can't call the callback on progress updates.
870
        return;
×
871
    }
872

873
    Action::Result action_result = action_result_from_command_result(command_result);
4✔
874

875
    if (callback) {
4✔
876
        auto temp_callback = callback;
4✔
877
        _system_impl->call_user_callback(
8✔
878
            [temp_callback, action_result]() { temp_callback(action_result); });
879
    }
4✔
880
}
881

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