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

mavlink / MAVSDK / 14878740874

07 May 2025 08:25AM UTC coverage: 44.24% (-0.02%) from 44.261%
14878740874

push

github

web-flow
Merge pull request #2567 from mavlink/pr-revert-yaw

Revert "[PATCH] Fix goto_location sending radians instead of degrees"

0 of 1 new or added line in 1 file covered. (0.0%)

8 existing lines in 2 files now uncovered.

14828 of 33517 relevant lines covered (44.24%)

281.37 hits per line

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

14.66
/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(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]() {
2✔
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.params.maybe_param2 = 1.0f; // reboot onboard computer
×
363
    command.params.maybe_param3 = 1.0f; // reboot camera
×
364
    command.params.maybe_param4 = 1.0f; // reboot gimbal
×
365
    command.target_component_id = _system_impl->get_autopilot_id();
×
366

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

373
void ActionImpl::shutdown_async(const Action::ResultCallback& callback) const
×
374
{
375
    MavlinkCommandSender::CommandLong command{};
×
376

377
    command.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
×
378
    command.params.maybe_param1 = 2.0f; // shutdown autopilot
×
379
    command.params.maybe_param2 = 2.0f; // shutdown onboard computer
×
380
    command.params.maybe_param3 = 2.0f; // shutdown camera
×
381
    command.params.maybe_param4 = 2.0f; // shutdown gimbal
×
382
    command.target_component_id = _system_impl->get_autopilot_id();
×
383

384
    _system_impl->send_command_async(
×
385
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
386
            command_result_callback(result, callback);
×
387
        });
×
388
}
×
389

390
void ActionImpl::takeoff_async(const Action::ResultCallback& callback) const
×
391
{
392
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
393
        takeoff_async_px4(callback);
×
394
    } else {
395
        takeoff_async_apm(callback);
×
396
    }
397
}
×
398

399
void ActionImpl::takeoff_async_px4(const Action::ResultCallback& callback) const
×
400
{
401
    MavlinkCommandSender::CommandLong command{};
×
402

403
    command.command = MAV_CMD_NAV_TAKEOFF;
×
404
    command.target_component_id = _system_impl->get_autopilot_id();
×
405

406
    _system_impl->send_command_async(
×
407
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
408
            command_result_callback(result, callback);
×
409
        });
×
410
}
×
411

412
void ActionImpl::takeoff_async_apm(const Action::ResultCallback& callback) const
×
413
{
414
    auto send_takeoff_command = [this, callback]() {
×
415
        MavlinkCommandSender::CommandLong command{};
×
416

417
        command.command = MAV_CMD_NAV_TAKEOFF;
×
418
        command.target_component_id = _system_impl->get_autopilot_id();
×
419
        command.params.maybe_param7 = get_takeoff_altitude().second;
×
420

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

444
void ActionImpl::land_async(const Action::ResultCallback& callback) const
×
445
{
446
    MavlinkCommandSender::CommandLong command{};
×
447

448
    command.command = MAV_CMD_NAV_LAND;
×
449
    command.params.maybe_param4 = NAN; // Don't change yaw.
×
450
    command.target_component_id = _system_impl->get_autopilot_id();
×
451

452
    _system_impl->send_command_async(
×
453
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
454
            command_result_callback(result, callback);
×
455
        });
×
456
}
×
457

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

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

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

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

511
    send_do_reposition();
×
512
}
×
513

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

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

534
    _system_impl->send_command_async(
×
535
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
536
            command_result_callback(result, callback);
×
537
        });
×
538
}
×
539

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

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

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

593
    _system_impl->send_command_async(
×
594
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
595
            command_result_callback(result, callback);
×
596
        });
×
597
}
598

599
void ActionImpl::transition_to_fixedwing_async(const Action::ResultCallback& callback) const
×
600
{
601
    if (!_vtol_transition_support_known) {
×
602
        if (callback) {
×
603
            callback(Action::Result::VtolTransitionSupportUnknown);
×
604
        }
605
        return;
×
606
    }
607

608
    if (!_vtol_transition_possible) {
×
609
        if (callback) {
×
610
            callback(Action::Result::NoVtolTransitionSupport);
×
611
        }
612
        return;
×
613
    }
614

615
    MavlinkCommandSender::CommandLong command{};
×
616

617
    command.command = MAV_CMD_DO_VTOL_TRANSITION;
×
618
    command.params.maybe_param1 = static_cast<float>(MAV_VTOL_STATE_FW);
×
619
    command.target_component_id = _system_impl->get_autopilot_id();
×
620

621
    _system_impl->send_command_async(
×
622
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
623
            command_result_callback(result, callback);
×
624
        });
×
625
}
626

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

636
    if (!_vtol_transition_possible) {
×
637
        if (callback) {
×
638
            callback(Action::Result::NoVtolTransitionSupport);
×
639
        }
640
        return;
×
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_MC);
×
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::process_extended_sys_state(const mavlink_message_t& message)
×
655
{
656
    mavlink_extended_sys_state_t extended_sys_state;
×
657
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
658

659
    if (extended_sys_state.vtol_state != MAV_VTOL_STATE_UNDEFINED) {
×
660
        _vtol_transition_possible = true;
×
661
    } else {
662
        _vtol_transition_possible = false;
×
663
    }
664
    _vtol_transition_support_known = true;
×
665
}
×
666

667
void ActionImpl::set_takeoff_altitude_async(
×
668
    const float relative_altitude_m, const Action::ResultCallback& callback)
669
{
670
    callback(set_takeoff_altitude(relative_altitude_m));
×
671
}
×
672

673
Action::Result ActionImpl::set_takeoff_altitude(float relative_altitude_m)
×
674
{
675
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
676
        return set_takeoff_altitude_px4(relative_altitude_m);
×
677
    } else {
678
        return set_takeoff_altitude_apm(relative_altitude_m);
×
679
    }
680
}
681

682
Action::Result ActionImpl::set_takeoff_altitude_px4(float relative_altitude_m)
×
683
{
684
    _takeoff_altitude = relative_altitude_m;
×
685

686
    const MavlinkParameterClient::Result result =
687
        _system_impl->set_param_float(TAKEOFF_ALT_PARAM, relative_altitude_m);
×
688
    return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
689
                                                                 Action::Result::ParameterError;
×
690
}
691

692
Action::Result ActionImpl::set_takeoff_altitude_apm(float relative_altitude_m)
×
693
{
694
    _takeoff_altitude = relative_altitude_m;
×
695
    return Action::Result::Success;
×
696
}
697

698
void ActionImpl::get_takeoff_altitude_async(
×
699
    const Action::GetTakeoffAltitudeCallback& callback) const
700
{
701
    auto altitude_result = get_takeoff_altitude();
×
702
    callback(altitude_result.first, altitude_result.second);
×
703
}
×
704

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

719
void ActionImpl::set_return_to_launch_altitude_async(
×
720
    const float relative_altitude_m, const Action::ResultCallback& callback) const
721
{
722
    callback(set_return_to_launch_altitude(relative_altitude_m));
×
723
}
×
724

725
Action::Result ActionImpl::set_return_to_launch_altitude(const float relative_altitude_m) const
×
726
{
727
    const MavlinkParameterClient::Result result =
728
        _system_impl->set_param_float(RTL_RETURN_ALTITUDE_PARAM, relative_altitude_m);
×
729
    return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
730
                                                                 Action::Result::ParameterError;
×
731
}
732

733
void ActionImpl::get_return_to_launch_altitude_async(
×
734
    const Action::GetReturnToLaunchAltitudeCallback& callback) const
735
{
736
    const auto get_result = get_return_to_launch_altitude();
×
737
    callback(get_result.first, get_result.second);
×
738
}
×
739

740
std::pair<Action::Result, float> ActionImpl::get_return_to_launch_altitude() const
×
741
{
742
    auto result = _system_impl->get_param_float(RTL_RETURN_ALTITUDE_PARAM);
×
743
    return std::make_pair<>(
×
744
        (result.first == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
745
                                                                    Action::Result::ParameterError,
746
        result.second);
×
747
}
748

749
void ActionImpl::set_current_speed_async(float speed_m_s, const Action::ResultCallback& callback)
×
750
{
751
    MavlinkCommandSender::CommandLong command{};
×
752

753
    command.command = MAV_CMD_DO_CHANGE_SPEED;
×
754
    command.params.maybe_param1 = 1.0f; // ground speed
×
755
    command.params.maybe_param2 = speed_m_s;
×
756
    command.params.maybe_param3 = -1.0f; // no throttle set
×
757
    command.params.maybe_param4 = 0.0f; // reserved
×
758
    command.target_component_id = _system_impl->get_autopilot_id();
×
759

760
    _system_impl->send_command_async(
×
761
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
762
            command_result_callback(result, callback);
×
763
        });
×
764
}
×
765

766
Action::Result ActionImpl::set_current_speed(float speed_m_s)
×
767
{
768
    auto prom = std::promise<Action::Result>();
×
769
    auto fut = prom.get_future();
×
770

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

773
    return fut.get();
×
774
}
×
775

776
Action::Result ActionImpl::action_result_from_command_result(MavlinkCommandSender::Result result)
4✔
777
{
778
    switch (result) {
4✔
779
        case MavlinkCommandSender::Result::Success:
2✔
780
            return Action::Result::Success;
2✔
781
        case MavlinkCommandSender::Result::NoSystem:
×
782
            return Action::Result::NoSystem;
×
783
        case MavlinkCommandSender::Result::ConnectionError:
×
784
            return Action::Result::ConnectionError;
×
785
        case MavlinkCommandSender::Result::Busy:
×
786
            return Action::Result::Busy;
×
787
        case MavlinkCommandSender::Result::Denied:
2✔
788
            // Fallthrough
789
        case MavlinkCommandSender::Result::TemporarilyRejected:
790
            return Action::Result::CommandDenied;
2✔
791
        case MavlinkCommandSender::Result::Failed:
×
792
            return Action::Result::Failed;
×
793
        case MavlinkCommandSender::Result::Timeout:
×
794
            return Action::Result::Timeout;
×
795
        case MavlinkCommandSender::Result::Unsupported:
×
796
            return Action::Result::Unsupported;
×
797
        default:
×
798
            return Action::Result::Unknown;
×
799
    }
800
}
801

802
void ActionImpl::command_result_callback(
4✔
803
    MavlinkCommandSender::Result command_result, const Action::ResultCallback& callback) const
804
{
805
    if (command_result == MavlinkCommandSender::Result::InProgress) {
4✔
806
        // We only want to return once, so we can't call the callback on progress updates.
807
        return;
×
808
    }
809

810
    Action::Result action_result = action_result_from_command_result(command_result);
4✔
811

812
    if (callback) {
4✔
813
        auto temp_callback = callback;
4✔
814
        _system_impl->call_user_callback(
8✔
815
            [temp_callback, action_result]() { temp_callback(action_result); });
816
    }
4✔
817
}
818

819
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2025 Coveralls, Inc