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

mavlink / MAVSDK / 20967493006

13 Jan 2026 06:10PM UTC coverage: 48.034% (-0.03%) from 48.064%
20967493006

Pull #2750

github

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

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

81 existing lines in 4 files now uncovered.

17740 of 36932 relevant lines covered (48.03%)

462.9 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([temp_callback = callback]() {
×
616
                temp_callback(Action::Result::InvalidArgument);
617
            });
618
        }
NEW
619
        return;
×
620
    }
NEW
621
    _system_impl->send_command_async(
×
NEW
622
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
NEW
623
            command_result_callback(result, callback);
×
NEW
624
        });
×
625
}
626

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

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

UNCOV
643
    MavlinkCommandSender::CommandLong command{};
×
644

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

801
    return fut.get();
×
UNCOV
802
}
×
803

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

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

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

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

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

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

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

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

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

870
    return fut.get();
×
UNCOV
871
}
×
872

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

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

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

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

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