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

mavlink / MAVSDK / 20970548015

13 Jan 2026 07:55PM UTC coverage: 47.983% (-0.08%) from 48.064%
20970548015

Pull #2750

github

web-flow
Merge 7019334dc into 968fec296
Pull Request #2750: Add set_relay action support

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

31 existing lines in 9 files now uncovered.

17721 of 36932 relevant lines covered (47.98%)

464.05 hits per line

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

13.42
/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

NEW
215
Action::Result ActionImpl::set_relay(const int index, const int setting)
×
216
{
NEW
217
    auto prom = std::promise<Action::Result>();
×
NEW
218
    auto fut = prom.get_future();
×
219

NEW
220
    set_relay_async(index, setting, [&prom](Action::Result result) { prom.set_value(result); });
×
221

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

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

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

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

235
Action::Result ActionImpl::transition_to_multicopter() const
×
236
{
237
    auto prom = std::promise<Action::Result>();
×
238
    auto fut = prom.get_future();
×
239

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

242
    return fut.get();
×
243
}
×
244

245
void ActionImpl::arm_async(const Action::ResultCallback& callback) const
2✔
246
{
247
    auto send_arm_command = [this, callback]() {
8✔
248
        MavlinkCommandSender::CommandLong command{};
2✔
249

250
        command.command = MAV_CMD_COMPONENT_ARM_DISARM;
2✔
251
        command.params.maybe_param1 = 1.0f; // arm
2✔
252
        command.target_component_id = _system_impl->get_autopilot_id();
2✔
253

254
        _system_impl->send_command_async(
4✔
255
            command, [this, callback](MavlinkCommandSender::Result result, float) {
2✔
256
                command_result_callback(result, callback);
2✔
257
            });
2✔
258
    };
2✔
259

260
    if (need_hold_before_arm()) {
2✔
261
        _system_impl->set_flight_mode_async(
×
262
            FlightMode::Hold,
263
            [callback, send_arm_command](MavlinkCommandSender::Result result, float) {
×
264
                Action::Result action_result = action_result_from_command_result(result);
×
265
                if (action_result != Action::Result::Success) {
×
266
                    if (callback) {
×
267
                        callback(action_result);
×
268
                    }
269
                }
270
                send_arm_command();
×
271
            });
×
272
        return;
×
273
    } else {
274
        send_arm_command();
2✔
275
    }
276
}
2✔
277

278
bool ActionImpl::need_hold_before_arm() const
2✔
279
{
280
    if (_system_impl->autopilot() == Autopilot::Px4) {
2✔
281
        return need_hold_before_arm_px4();
×
282
    } else {
283
        return need_hold_before_arm_apm();
2✔
284
    }
285
}
286

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

297
bool ActionImpl::need_hold_before_arm_apm() const
2✔
298
{
299
    if (_system_impl->get_flight_mode() == FlightMode::Mission ||
4✔
300
        _system_impl->get_flight_mode() == FlightMode::ReturnToLaunch ||
4✔
301
        _system_impl->get_flight_mode() == FlightMode::Land) {
2✔
302
        return true;
×
303
    } else {
304
        return false;
2✔
305
    }
306
}
307

308
void ActionImpl::arm_force_async(const Action::ResultCallback& callback) const
×
309
{
310
    MavlinkCommandSender::CommandLong command{};
×
311

312
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
×
313
    command.params.maybe_param1 = 0.0f; // arm
×
314
    command.params.maybe_param2 = 21196.f; // magic number to force
×
315
    command.target_component_id = _system_impl->get_autopilot_id();
×
316

317
    _system_impl->send_command_async(
×
318
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
319
            command_result_callback(result, callback);
×
320
        });
×
321
}
×
322

323
void ActionImpl::disarm_async(const Action::ResultCallback& callback) const
2✔
324
{
325
    MavlinkCommandSender::CommandLong command{};
2✔
326

327
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
2✔
328
    command.params.maybe_param1 = 0.0f; // disarm
2✔
329
    command.target_component_id = _system_impl->get_autopilot_id();
2✔
330

331
    _system_impl->send_command_async(
2✔
332
        command, [this, callback](MavlinkCommandSender::Result result, float) {
2✔
333
            command_result_callback(result, callback);
2✔
334
        });
2✔
335
}
2✔
336

337
void ActionImpl::terminate_async(const Action::ResultCallback& callback) const
×
338
{
339
    MavlinkCommandSender::CommandLong command{};
×
340

341
    command.command = MAV_CMD_DO_FLIGHTTERMINATION;
×
342
    command.params.maybe_param1 = 1.0f;
×
343
    command.target_component_id = _system_impl->get_autopilot_id();
×
344

345
    _system_impl->send_command_async(
×
346
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
347
            command_result_callback(result, callback);
×
348
        });
×
349
}
×
350

351
void ActionImpl::kill_async(const Action::ResultCallback& callback) const
×
352
{
353
    MavlinkCommandSender::CommandLong command{};
×
354

355
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
×
356
    command.params.maybe_param1 = 0.0f; // kill
×
357
    command.params.maybe_param2 = 21196.f; // magic number to enforce in-air
×
358
    command.target_component_id = _system_impl->get_autopilot_id();
×
359

360
    _system_impl->send_command_async(
×
361
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
362
            command_result_callback(result, callback);
×
363
        });
×
364
}
×
365

366
void ActionImpl::reboot_async(const Action::ResultCallback& callback) const
×
367
{
368
    MavlinkCommandSender::CommandLong command{};
×
369

370
    command.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
×
371
    command.params.maybe_param1 = 1.0f; // reboot autopilot
×
372
    command.target_component_id = _system_impl->get_autopilot_id();
×
373

374
    _system_impl->send_command_async(
×
375
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
376
            command_result_callback(result, callback);
×
377
        });
×
378
}
×
379

380
void ActionImpl::shutdown_async(const Action::ResultCallback& callback) const
×
381
{
382
    MavlinkCommandSender::CommandLong command{};
×
383

384
    command.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
×
385
    command.params.maybe_param1 = 2.0f; // shutdown autopilot
×
386
    command.target_component_id = _system_impl->get_autopilot_id();
×
387

388
    _system_impl->send_command_async(
×
389
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
390
            command_result_callback(result, callback);
×
391
        });
×
392
}
×
393

394
void ActionImpl::takeoff_async(const Action::ResultCallback& callback) const
×
395
{
396
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
397
        takeoff_async_px4(callback);
×
398
    } else {
399
        takeoff_async_apm(callback);
×
400
    }
401
}
×
402

403
void ActionImpl::takeoff_async_px4(const Action::ResultCallback& callback) const
×
404
{
405
    MavlinkCommandSender::CommandLong command{};
×
406

407
    command.command = MAV_CMD_NAV_TAKEOFF;
×
408
    command.target_component_id = _system_impl->get_autopilot_id();
×
409

410
    _system_impl->send_command_async(
×
411
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
412
            command_result_callback(result, callback);
×
413
        });
×
414
}
×
415

416
void ActionImpl::takeoff_async_apm(const Action::ResultCallback& callback) const
×
417
{
418
    auto send_takeoff_command = [this, callback]() {
×
419
        MavlinkCommandSender::CommandLong command{};
×
420

421
        command.command = MAV_CMD_NAV_TAKEOFF;
×
422
        command.target_component_id = _system_impl->get_autopilot_id();
×
423
        command.params.maybe_param7 = get_takeoff_altitude().second;
×
424

425
        _system_impl->send_command_async(
×
426
            command, [this, callback](MavlinkCommandSender::Result result, float) {
×
427
                command_result_callback(result, callback);
×
428
            });
×
429
    };
×
430
    if (_system_impl->get_flight_mode() != FlightMode::Offboard) {
×
431
        _system_impl->set_flight_mode_async(
×
432
            FlightMode::Offboard,
433
            [callback, send_takeoff_command](MavlinkCommandSender::Result result, float) {
×
434
                Action::Result action_result = action_result_from_command_result(result);
×
435
                if (action_result != Action::Result::Success) {
×
436
                    if (callback) {
×
437
                        callback(action_result);
×
438
                    }
439
                } else {
440
                    send_takeoff_command();
×
441
                }
442
            });
×
443
    } else {
444
        send_takeoff_command();
×
445
    }
446
}
×
447

448
void ActionImpl::land_async(const Action::ResultCallback& callback) const
×
449
{
450
    MavlinkCommandSender::CommandLong command{};
×
451

452
    command.command = MAV_CMD_NAV_LAND;
×
453
    command.params.maybe_param4 = NAN; // Don't change yaw.
×
454
    command.target_component_id = _system_impl->get_autopilot_id();
×
455

456
    _system_impl->send_command_async(
×
457
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
458
            command_result_callback(result, callback);
×
459
        });
×
460
}
×
461

462
void ActionImpl::return_to_launch_async(const Action::ResultCallback& callback) const
×
463
{
464
    _system_impl->set_flight_mode_async(
×
465
        FlightMode::ReturnToLaunch, [this, callback](MavlinkCommandSender::Result result, float) {
×
466
            command_result_callback(result, callback);
×
467
        });
×
468
}
×
469

470
void ActionImpl::goto_location_async(
×
471
    const double latitude_deg,
472
    const double longitude_deg,
473
    const float altitude_amsl_m,
474
    const float yaw_deg,
475
    const Action::ResultCallback& callback)
476
{
477
    auto send_do_reposition =
478
        [this, callback, yaw_deg, latitude_deg, longitude_deg, altitude_amsl_m]() {
×
479
            MavlinkCommandSender::CommandInt command{};
×
480

481
            command.command = MAV_CMD_DO_REPOSITION;
×
482
            command.target_component_id = _system_impl->get_autopilot_id();
×
483
            command.frame = MAV_FRAME_GLOBAL_INT;
×
484
            command.params.maybe_param4 = static_cast<float>(to_rad_from_deg(yaw_deg));
×
485
            command.params.x = int32_t(std::round(latitude_deg * 1e7));
×
486
            command.params.y = int32_t(std::round(longitude_deg * 1e7));
×
487
            command.params.maybe_z = altitude_amsl_m;
×
488
            command.params.maybe_param2 = static_cast<float>(MAV_DO_REPOSITION_FLAGS_CHANGE_MODE);
×
489

490
            _system_impl->send_command_async(
×
491
                command, [this, callback](MavlinkCommandSender::Result result, float) {
×
492
                    command_result_callback(result, callback);
×
493
                });
×
494
        };
×
495
    FlightMode goto_flight_mode;
496
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
497
        goto_flight_mode = FlightMode::Hold;
×
498
    } else {
499
        goto_flight_mode = FlightMode::Offboard;
×
500
    }
501
    if (_system_impl->get_flight_mode() != goto_flight_mode) {
×
502
        _system_impl->set_flight_mode_async(
×
503
            goto_flight_mode,
504
            [this, callback, send_do_reposition](MavlinkCommandSender::Result result, float) {
×
505
                Action::Result action_result = action_result_from_command_result(result);
×
506
                if (action_result != Action::Result::Success) {
×
507
                    command_result_callback(result, callback);
×
508
                    return;
×
509
                }
510
                send_do_reposition();
×
511
            });
512
        return;
×
513
    }
514

515
    send_do_reposition();
×
516
}
×
517

518
void ActionImpl::do_orbit_async(
×
519
    const float radius_m,
520
    const float velocity_ms,
521
    const Action::OrbitYawBehavior yaw_behavior,
522
    const double latitude_deg,
523
    const double longitude_deg,
524
    const double absolute_altitude_m,
525
    const Action::ResultCallback& callback)
526
{
527
    MavlinkCommandSender::CommandInt command{};
×
528

529
    command.command = MAV_CMD_DO_ORBIT;
×
530
    command.target_component_id = _system_impl->get_autopilot_id();
×
531
    command.params.maybe_param1 = radius_m;
×
532
    command.params.maybe_param2 = velocity_ms;
×
533
    command.params.maybe_param3 = static_cast<float>(yaw_behavior);
×
534
    command.params.x = int32_t(std::round(latitude_deg * 1e7));
×
535
    command.params.y = int32_t(std::round(longitude_deg * 1e7));
×
536
    command.params.maybe_z = static_cast<float>(absolute_altitude_m);
×
537

538
    _system_impl->send_command_async(
×
539
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
540
            command_result_callback(result, callback);
×
541
        });
×
542
}
×
543

544
void ActionImpl::hold_async(const Action::ResultCallback& callback) const
×
545
{
546
    _system_impl->set_flight_mode_async(
×
547
        FlightMode::Hold, [this, callback](MavlinkCommandSender::Result result, float) {
×
548
            command_result_callback(result, callback);
×
549
        });
×
550
}
×
551

552
void ActionImpl::set_actuator_async(
×
553
    const int index, const float value, const Action::ResultCallback& callback)
554
{
555
    MavlinkCommandSender::CommandLong command{};
×
556
    command.target_component_id = _system_impl->get_autopilot_id();
×
557

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

597
    _system_impl->send_command_async(
×
598
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
599
            command_result_callback(result, callback);
×
600
        });
×
601
}
602

NEW
603
void ActionImpl::set_relay_async(
×
604
    const int index, const int setting, const Action::ResultCallback& callback)
605
{
NEW
606
    MavlinkCommandSender::CommandLong command{};
×
NEW
607
    command.target_component_id = _system_impl->get_autopilot_id();
×
608

NEW
609
    if (setting >= 0) {
×
NEW
610
        command.command = MAV_CMD_DO_SET_RELAY;
×
NEW
611
        command.params.maybe_param1 = static_cast<float>(index);
×
NEW
612
        command.params.maybe_param2 = setting;
×
613
    } else {
NEW
614
        if (callback) {
×
NEW
615
            _system_impl->call_user_callback(
×
616
                [temp_callback = callback]() { temp_callback(Action::Result::InvalidArgument); });
617
        }
NEW
618
        return;
×
619
    }
NEW
620
    _system_impl->send_command_async(
×
NEW
621
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
NEW
622
            command_result_callback(result, callback);
×
NEW
623
        });
×
624
}
625

UNCOV
626
void ActionImpl::transition_to_fixedwing_async(const Action::ResultCallback& callback) const
×
627
{
628
    if (!_vtol_transition_support_known) {
×
629
        if (callback) {
×
630
            callback(Action::Result::VtolTransitionSupportUnknown);
×
631
        }
632
        return;
×
633
    }
634

635
    if (!_vtol_transition_possible) {
×
636
        if (callback) {
×
637
            callback(Action::Result::NoVtolTransitionSupport);
×
638
        }
639
        return;
×
640
    }
641

642
    MavlinkCommandSender::CommandLong command{};
×
643

644
    command.command = MAV_CMD_DO_VTOL_TRANSITION;
×
645
    command.params.maybe_param1 = static_cast<float>(MAV_VTOL_STATE_FW);
×
646
    command.target_component_id = _system_impl->get_autopilot_id();
×
647

648
    _system_impl->send_command_async(
×
649
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
650
            command_result_callback(result, callback);
×
651
        });
×
652
}
653

654
void ActionImpl::transition_to_multicopter_async(const Action::ResultCallback& callback) const
×
655
{
656
    if (!_vtol_transition_support_known) {
×
657
        if (callback) {
×
658
            callback(Action::Result::VtolTransitionSupportUnknown);
×
659
        }
660
        return;
×
661
    }
662

663
    if (!_vtol_transition_possible) {
×
664
        if (callback) {
×
665
            callback(Action::Result::NoVtolTransitionSupport);
×
666
        }
667
        return;
×
668
    }
669
    MavlinkCommandSender::CommandLong command{};
×
670

671
    command.command = MAV_CMD_DO_VTOL_TRANSITION;
×
672
    command.params.maybe_param1 = static_cast<float>(MAV_VTOL_STATE_MC);
×
673
    command.target_component_id = _system_impl->get_autopilot_id();
×
674

675
    _system_impl->send_command_async(
×
676
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
677
            command_result_callback(result, callback);
×
678
        });
×
679
}
680

681
void ActionImpl::process_extended_sys_state(const mavlink_message_t& message)
×
682
{
683
    mavlink_extended_sys_state_t extended_sys_state;
684
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
685

686
    if (extended_sys_state.vtol_state != MAV_VTOL_STATE_UNDEFINED) {
×
687
        _vtol_transition_possible = true;
×
688
    } else {
689
        _vtol_transition_possible = false;
×
690
    }
691
    _vtol_transition_support_known = true;
×
692
}
×
693

694
void ActionImpl::set_takeoff_altitude_async(
×
695
    const float relative_altitude_m, const Action::ResultCallback& callback)
696
{
697
    callback(set_takeoff_altitude(relative_altitude_m));
×
698
}
×
699

700
Action::Result ActionImpl::set_takeoff_altitude(float relative_altitude_m)
×
701
{
702
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
703
        return set_takeoff_altitude_px4(relative_altitude_m);
×
704
    } else {
705
        return set_takeoff_altitude_apm(relative_altitude_m);
×
706
    }
707
}
708

709
Action::Result ActionImpl::set_takeoff_altitude_px4(float relative_altitude_m)
×
710
{
711
    _takeoff_altitude = relative_altitude_m;
×
712

713
    const MavlinkParameterClient::Result result =
714
        _system_impl->set_param_float(TAKEOFF_ALT_PARAM, relative_altitude_m);
×
715
    return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
716
                                                                 Action::Result::ParameterError;
×
717
}
718

719
Action::Result ActionImpl::set_takeoff_altitude_apm(float relative_altitude_m)
×
720
{
721
    _takeoff_altitude = relative_altitude_m;
×
722
    return Action::Result::Success;
×
723
}
724

725
void ActionImpl::get_takeoff_altitude_async(
×
726
    const Action::GetTakeoffAltitudeCallback& callback) const
727
{
728
    auto altitude_result = get_takeoff_altitude();
×
729
    callback(altitude_result.first, altitude_result.second);
×
730
}
×
731

732
std::pair<Action::Result, float> ActionImpl::get_takeoff_altitude() const
×
733
{
734
    if (_system_impl->autopilot() == Autopilot::ArduPilot) {
×
735
        return std::make_pair<>(Action::Result::Success, _takeoff_altitude);
×
736
    } else {
737
        auto result = _system_impl->get_param_float(TAKEOFF_ALT_PARAM);
×
738
        return std::make_pair<>(
×
739
            (result.first == MavlinkParameterClient::Result::Success) ?
×
740
                Action::Result::Success :
741
                Action::Result::ParameterError,
742
            result.second);
×
743
    }
744
}
745

746
void ActionImpl::set_return_to_launch_altitude_async(
×
747
    const float relative_altitude_m, const Action::ResultCallback& callback) const
748
{
749
    callback(set_return_to_launch_altitude(relative_altitude_m));
×
750
}
×
751

752
Action::Result ActionImpl::set_return_to_launch_altitude(const float relative_altitude_m) const
×
753
{
754
    const MavlinkParameterClient::Result result =
755
        _system_impl->set_param_float(RTL_RETURN_ALTITUDE_PARAM, relative_altitude_m);
×
756
    return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
757
                                                                 Action::Result::ParameterError;
×
758
}
759

760
void ActionImpl::get_return_to_launch_altitude_async(
×
761
    const Action::GetReturnToLaunchAltitudeCallback& callback) const
762
{
763
    const auto get_result = get_return_to_launch_altitude();
×
764
    callback(get_result.first, get_result.second);
×
765
}
×
766

767
std::pair<Action::Result, float> ActionImpl::get_return_to_launch_altitude() const
×
768
{
769
    auto result = _system_impl->get_param_float(RTL_RETURN_ALTITUDE_PARAM);
×
770
    return std::make_pair<>(
×
771
        (result.first == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
772
                                                                    Action::Result::ParameterError,
773
        result.second);
×
774
}
775

776
void ActionImpl::set_current_speed_async(float speed_m_s, const Action::ResultCallback& callback)
×
777
{
778
    MavlinkCommandSender::CommandLong command{};
×
779

780
    command.command = MAV_CMD_DO_CHANGE_SPEED;
×
781
    command.params.maybe_param1 = 1.0f; // ground speed
×
782
    command.params.maybe_param2 = speed_m_s;
×
783
    command.params.maybe_param3 = -1.0f; // no throttle set
×
784
    command.params.maybe_param4 = 0.0f; // reserved
×
785
    command.target_component_id = _system_impl->get_autopilot_id();
×
786

787
    _system_impl->send_command_async(
×
788
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
789
            command_result_callback(result, callback);
×
790
        });
×
791
}
×
792

793
Action::Result ActionImpl::set_current_speed(float speed_m_s)
×
794
{
795
    auto prom = std::promise<Action::Result>();
×
796
    auto fut = prom.get_future();
×
797

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

800
    return fut.get();
×
801
}
×
802

803
Action::Result ActionImpl::set_gps_global_origin(
×
804
    double latitude_deg, double longitude_deg, float absolute_altitude_m) const
805
{
806
    const int32_t latitude_e7 = static_cast<int32_t>(std::round(latitude_deg * 1e7));
×
807
    const int32_t longitude_e7 = static_cast<int32_t>(std::round(longitude_deg * 1e7));
×
808
    const int32_t altitude_mm = static_cast<int32_t>(std::round(absolute_altitude_m * 1000.0f));
×
809

810
    auto prom = std::promise<Action::Result>();
×
811
    auto fut = prom.get_future();
×
812
    std::atomic<bool> prom_already_set{false};
×
813

814
    // Use a unique cookie for this handler
815
    const void* cookie = this;
×
816

817
    // Register handler for GPS_GLOBAL_ORIGIN response.
818
    // Note: Older PX4 versions (pre-v1.17) had a race condition where they would
819
    // broadcast GPS_GLOBAL_ORIGIN with stale values immediately after receiving
820
    // SET_GPS_GLOBAL_ORIGIN, before EKF2 had processed the command. To handle
821
    // this, we wait for a response with matching values rather than accepting
822
    // the first response.
823
    _system_impl->register_mavlink_message_handler(
×
824
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
825
        [&prom, &prom_already_set, latitude_e7, longitude_e7, altitude_mm](
×
826
            const mavlink_message_t& message) {
×
827
            mavlink_gps_global_origin_t origin;
828
            mavlink_msg_gps_global_origin_decode(&message, &origin);
×
829

830
            // Only signal success when we receive the values we set
831
            if (origin.latitude == latitude_e7 && origin.longitude == longitude_e7 &&
×
832
                origin.altitude == altitude_mm) {
×
833
                if (!prom_already_set.exchange(true)) {
×
834
                    prom.set_value(Action::Result::Success);
×
835
                }
836
            }
837
            // Otherwise, keep waiting for the correct values (or timeout)
838
        },
×
839
        cookie);
840

841
    // Send the SET_GPS_GLOBAL_ORIGIN message
842
    if (!_system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
843
            mavlink_message_t message;
844
            mavlink_msg_set_gps_global_origin_pack_chan(
×
845
                mavlink_address.system_id,
×
846
                mavlink_address.component_id,
×
847
                channel,
848
                &message,
849
                _system_impl->get_system_id(),
×
850
                latitude_e7,
×
851
                longitude_e7,
×
852
                altitude_mm,
×
853
                0);
854
            return message;
×
855
        })) {
856
        _system_impl->unregister_mavlink_message_handler(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, cookie);
×
857
        return Action::Result::ConnectionError;
×
858
    }
859

860
    // Wait for response with timeout
861
    auto status = fut.wait_for(std::chrono::duration<double>(_system_impl->timeout_s()));
×
862

863
    _system_impl->unregister_mavlink_message_handler(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, cookie);
×
864

865
    if (status == std::future_status::timeout) {
×
866
        return Action::Result::Timeout;
×
867
    }
868

869
    return fut.get();
×
870
}
×
871

872
Action::Result ActionImpl::action_result_from_command_result(MavlinkCommandSender::Result result)
4✔
873
{
874
    switch (result) {
4✔
875
        case MavlinkCommandSender::Result::Success:
2✔
876
            return Action::Result::Success;
2✔
877
        case MavlinkCommandSender::Result::NoSystem:
×
878
            return Action::Result::NoSystem;
×
879
        case MavlinkCommandSender::Result::ConnectionError:
×
880
            return Action::Result::ConnectionError;
×
881
        case MavlinkCommandSender::Result::Busy:
×
882
            return Action::Result::Busy;
×
883
        case MavlinkCommandSender::Result::Denied:
2✔
884
            // Fallthrough
885
        case MavlinkCommandSender::Result::TemporarilyRejected:
886
            return Action::Result::CommandDenied;
2✔
887
        case MavlinkCommandSender::Result::Failed:
×
888
            return Action::Result::Failed;
×
889
        case MavlinkCommandSender::Result::Timeout:
×
890
            return Action::Result::Timeout;
×
891
        case MavlinkCommandSender::Result::Unsupported:
×
892
            return Action::Result::Unsupported;
×
893
        default:
×
894
            return Action::Result::Unknown;
×
895
    }
896
}
897

898
void ActionImpl::command_result_callback(
4✔
899
    MavlinkCommandSender::Result command_result, const Action::ResultCallback& callback) const
900
{
901
    if (command_result == MavlinkCommandSender::Result::InProgress) {
4✔
902
        // We only want to return once, so we can't call the callback on progress updates.
903
        return;
×
904
    }
905

906
    Action::Result action_result = action_result_from_command_result(command_result);
4✔
907

908
    if (callback) {
4✔
909
        auto temp_callback = callback;
4✔
910
        _system_impl->call_user_callback(
8✔
911
            [temp_callback, action_result]() { temp_callback(action_result); });
912
    }
4✔
913
}
914

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