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

mavlink / MAVSDK / 6736239309

02 Nov 2023 05:35PM UTC coverage: 31.229% (+0.07%) from 31.159%
6736239309

push

github

web-flow
Merge pull request #2170 from Jaeyoung-Lim/pr-fix-do-reposition

Request mode change for action MAV_CMD_DO_REPOSITION

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

7906 of 25316 relevant lines covered (31.23%)

23.6 hits per line

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

14.62
/src/mavsdk/plugins/action/action_impl.cpp
1
#include "action_impl.h"
2
#include "mavsdk_impl.h"
3
#include "mavsdk_math.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()
1✔
22
{
23
    _system_impl->unregister_plugin(this);
1✔
24
}
1✔
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>();
4✔
58
    auto fut = prom.get_future();
4✔
59

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

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

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

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

72
    return fut.get();
2✔
73
}
74

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

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

82
    return fut.get();
×
83
}
84

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

145
Action::Result ActionImpl::goto_location(
×
146
    const double latitude_deg,
147
    const double longitude_deg,
148
    const float altitude_amsl_m,
149
    const float yaw_deg)
150
{
151
    auto prom = std::promise<Action::Result>();
×
152
    auto fut = prom.get_future();
×
153

154
    goto_location_async(
×
155
        latitude_deg, longitude_deg, altitude_amsl_m, yaw_deg, [&prom](Action::Result result) {
×
156
            prom.set_value(result);
×
157
        });
×
158

159
    return fut.get();
×
160
}
161

162
Action::Result ActionImpl::do_orbit(
×
163
    const float radius_m,
164
    const float velocity_ms,
165
    const Action::OrbitYawBehavior yaw_behavior,
166
    const double latitude_deg,
167
    const double longitude_deg,
168
    const double absolute_altitude_m)
169
{
170
    auto prom = std::promise<Action::Result>();
×
171
    auto fut = prom.get_future();
×
172

173
    do_orbit_async(
×
174
        radius_m,
175
        velocity_ms,
176
        yaw_behavior,
177
        latitude_deg,
178
        longitude_deg,
179
        absolute_altitude_m,
180
        [&prom](Action::Result result) { prom.set_value(result); });
×
181

182
    return fut.get();
×
183
}
184

185
Action::Result ActionImpl::hold() const
×
186
{
187
    auto prom = std::promise<Action::Result>();
×
188
    auto fut = prom.get_future();
×
189

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

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

195
Action::Result ActionImpl::set_actuator(const int index, const float value)
×
196
{
197
    auto prom = std::promise<Action::Result>();
×
198
    auto fut = prom.get_future();
×
199

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

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

205
Action::Result ActionImpl::transition_to_fixedwing() const
×
206
{
207
    auto prom = std::promise<Action::Result>();
×
208
    auto fut = prom.get_future();
×
209

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

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

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

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

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

225
void ActionImpl::arm_async(const Action::ResultCallback& callback) const
2✔
226
{
227
    auto send_arm_command = [this, callback]() {
2✔
228
        MavlinkCommandSender::CommandLong command{};
2✔
229

230
        command.command = MAV_CMD_COMPONENT_ARM_DISARM;
2✔
231
        command.params.maybe_param1 = 1.0f; // arm
2✔
232
        command.target_component_id = _system_impl->get_autopilot_id();
2✔
233

234
        _system_impl->send_command_async(
4✔
235
            command, [this, callback](MavlinkCommandSender::Result result, float) {
2✔
236
                command_result_callback(result, callback);
2✔
237
            });
2✔
238
    };
2✔
239

240
    if (need_hold_before_arm()) {
2✔
241
        _system_impl->set_flight_mode_async(
×
242
            FlightMode::Hold,
243
            [callback, send_arm_command](MavlinkCommandSender::Result result, float) {
×
244
                Action::Result action_result = action_result_from_command_result(result);
×
245
                if (action_result != Action::Result::Success) {
×
246
                    if (callback) {
×
247
                        callback(action_result);
×
248
                    }
249
                }
250
                send_arm_command();
×
251
            });
×
252
        return;
×
253
    } else {
254
        send_arm_command();
2✔
255
    }
256
}
257

258
bool ActionImpl::need_hold_before_arm() const
2✔
259
{
260
    if (_system_impl->autopilot() == Autopilot::Px4) {
2✔
261
        return need_hold_before_arm_px4();
×
262
    } else {
263
        return need_hold_before_arm_apm();
2✔
264
    }
265
}
266

267
bool ActionImpl::need_hold_before_arm_px4() const
×
268
{
269
    if (_system_impl->get_flight_mode() == FlightMode::Mission ||
×
270
        _system_impl->get_flight_mode() == FlightMode::ReturnToLaunch) {
×
271
        return true;
×
272
    } else {
273
        return false;
×
274
    }
275
}
276

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

288
void ActionImpl::disarm_async(const Action::ResultCallback& callback) const
2✔
289
{
290
    MavlinkCommandSender::CommandLong command{};
2✔
291

292
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
2✔
293
    command.params.maybe_param1 = 0.0f; // disarm
2✔
294
    command.target_component_id = _system_impl->get_autopilot_id();
2✔
295

296
    _system_impl->send_command_async(
2✔
297
        command, [this, callback](MavlinkCommandSender::Result result, float) {
2✔
298
            command_result_callback(result, callback);
2✔
299
        });
2✔
300
}
2✔
301

302
void ActionImpl::terminate_async(const Action::ResultCallback& callback) const
×
303
{
304
    MavlinkCommandSender::CommandLong command{};
×
305

306
    command.command = MAV_CMD_DO_FLIGHTTERMINATION;
×
307
    command.params.maybe_param1 = 1.0f;
×
308
    command.target_component_id = _system_impl->get_autopilot_id();
×
309

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

316
void ActionImpl::kill_async(const Action::ResultCallback& callback) const
×
317
{
318
    MavlinkCommandSender::CommandLong command{};
×
319

320
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
×
321
    command.params.maybe_param1 = 0.0f; // kill
×
322
    command.params.maybe_param2 = 21196.f; // magic number to enforce in-air
×
323
    command.target_component_id = _system_impl->get_autopilot_id();
×
324

325
    _system_impl->send_command_async(
×
326
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
327
            command_result_callback(result, callback);
×
328
        });
×
329
}
×
330

331
void ActionImpl::reboot_async(const Action::ResultCallback& callback) const
×
332
{
333
    MavlinkCommandSender::CommandLong command{};
×
334

335
    command.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
×
336
    command.params.maybe_param1 = 1.0f; // reboot autopilot
×
337
    command.params.maybe_param2 = 1.0f; // reboot onboard computer
×
338
    command.params.maybe_param3 = 1.0f; // reboot camera
×
339
    command.params.maybe_param4 = 1.0f; // reboot gimbal
×
340
    command.target_component_id = _system_impl->get_autopilot_id();
×
341

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

348
void ActionImpl::shutdown_async(const Action::ResultCallback& callback) const
×
349
{
350
    MavlinkCommandSender::CommandLong command{};
×
351

352
    command.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
×
353
    command.params.maybe_param1 = 2.0f; // shutdown autopilot
×
354
    command.params.maybe_param2 = 2.0f; // shutdown onboard computer
×
355
    command.params.maybe_param3 = 2.0f; // shutdown camera
×
356
    command.params.maybe_param4 = 2.0f; // shutdown gimbal
×
357
    command.target_component_id = _system_impl->get_autopilot_id();
×
358

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

365
void ActionImpl::takeoff_async(const Action::ResultCallback& callback) const
×
366
{
367
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
368
        takeoff_async_px4(callback);
×
369
    } else {
370
        takeoff_async_apm(callback);
×
371
    }
372
}
×
373

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

378
    command.command = MAV_CMD_NAV_TAKEOFF;
×
379
    command.target_component_id = _system_impl->get_autopilot_id();
×
380

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

387
void ActionImpl::takeoff_async_apm(const Action::ResultCallback& callback) const
×
388
{
389
    auto send_takeoff_command = [this, callback]() {
×
390
        MavlinkCommandSender::CommandLong command{};
×
391

392
        command.command = MAV_CMD_NAV_TAKEOFF;
×
393
        command.target_component_id = _system_impl->get_autopilot_id();
×
394
        command.params.maybe_param7 = get_takeoff_altitude().second;
×
395

396
        _system_impl->send_command_async(
×
397
            command, [this, callback](MavlinkCommandSender::Result result, float) {
×
398
                command_result_callback(result, callback);
×
399
            });
×
400
    };
×
401
    if (_system_impl->get_flight_mode() != FlightMode::Offboard) {
×
402
        _system_impl->set_flight_mode_async(
×
403
            FlightMode::Offboard,
404
            [callback, send_takeoff_command](MavlinkCommandSender::Result result, float) {
×
405
                Action::Result action_result = action_result_from_command_result(result);
×
406
                if (action_result != Action::Result::Success) {
×
407
                    if (callback) {
×
408
                        callback(action_result);
×
409
                    }
410
                }
411
                send_takeoff_command();
×
412
            });
×
413
    } else {
414
        send_takeoff_command();
×
415
    }
416
}
×
417

418
void ActionImpl::land_async(const Action::ResultCallback& callback) const
×
419
{
420
    MavlinkCommandSender::CommandLong command{};
×
421

422
    command.command = MAV_CMD_NAV_LAND;
×
423
    command.params.maybe_param4 = NAN; // Don't change yaw.
×
424
    command.target_component_id = _system_impl->get_autopilot_id();
×
425

426
    _system_impl->send_command_async(
×
427
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
428
            command_result_callback(result, callback);
×
429
        });
×
430
}
×
431

432
void ActionImpl::return_to_launch_async(const Action::ResultCallback& callback) const
×
433
{
434
    _system_impl->set_flight_mode_async(
×
435
        FlightMode::ReturnToLaunch, [this, callback](MavlinkCommandSender::Result result, float) {
×
436
            command_result_callback(result, callback);
×
437
        });
×
438
}
×
439

440
void ActionImpl::goto_location_async(
×
441
    const double latitude_deg,
442
    const double longitude_deg,
443
    const float altitude_amsl_m,
444
    const float yaw_deg,
445
    const Action::ResultCallback& callback)
446
{
447
    auto send_do_reposition =
×
448
        [this, callback, yaw_deg, latitude_deg, longitude_deg, altitude_amsl_m]() {
×
449
            MavlinkCommandSender::CommandInt command{};
×
450

451
            command.command = MAV_CMD_DO_REPOSITION;
×
452
            command.target_component_id = _system_impl->get_autopilot_id();
×
453
            command.frame = MAV_FRAME_GLOBAL_INT;
×
454
            command.params.maybe_param4 = static_cast<float>(to_rad_from_deg(yaw_deg));
×
455
            command.params.x = int32_t(std::round(latitude_deg * 1e7));
×
456
            command.params.y = int32_t(std::round(longitude_deg * 1e7));
×
457
            command.params.maybe_z = altitude_amsl_m;
×
458
            command.params.maybe_param2 = static_cast<float>(MAV_DO_REPOSITION_FLAGS_CHANGE_MODE);
×
459

460
            _system_impl->send_command_async(
×
461
                command, [this, callback](MavlinkCommandSender::Result result, float) {
×
462
                    command_result_callback(result, callback);
×
463
                });
×
464
        };
×
465
    FlightMode goto_flight_mode;
466
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
467
        goto_flight_mode = FlightMode::Hold;
×
468
    } else {
469
        goto_flight_mode = FlightMode::Offboard;
×
470
    }
471
    if (_system_impl->get_flight_mode() != goto_flight_mode) {
×
472
        _system_impl->set_flight_mode_async(
×
473
            goto_flight_mode,
474
            [this, callback, send_do_reposition](MavlinkCommandSender::Result result, float) {
×
475
                Action::Result action_result = action_result_from_command_result(result);
×
476
                if (action_result != Action::Result::Success) {
×
477
                    command_result_callback(result, callback);
×
478
                    return;
×
479
                }
480
                send_do_reposition();
×
481
            });
482
        return;
×
483
    }
484

485
    send_do_reposition();
×
486
}
487

488
void ActionImpl::do_orbit_async(
×
489
    const float radius_m,
490
    const float velocity_ms,
491
    const Action::OrbitYawBehavior yaw_behavior,
492
    const double latitude_deg,
493
    const double longitude_deg,
494
    const double absolute_altitude_m,
495
    const Action::ResultCallback& callback)
496
{
497
    MavlinkCommandSender::CommandInt command{};
×
498

499
    command.command = MAV_CMD_DO_ORBIT;
×
500
    command.target_component_id = _system_impl->get_autopilot_id();
×
501
    command.params.maybe_param1 = radius_m;
×
502
    command.params.maybe_param2 = velocity_ms;
×
503
    command.params.maybe_param3 = static_cast<float>(yaw_behavior);
×
504
    command.params.x = int32_t(std::round(latitude_deg * 1e7));
×
505
    command.params.y = int32_t(std::round(longitude_deg * 1e7));
×
506
    command.params.maybe_z = static_cast<float>(absolute_altitude_m);
×
507

508
    _system_impl->send_command_async(
×
509
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
510
            command_result_callback(result, callback);
×
511
        });
×
512
}
×
513

514
void ActionImpl::hold_async(const Action::ResultCallback& callback) const
×
515
{
516
    _system_impl->set_flight_mode_async(
×
517
        FlightMode::Hold, [this, callback](MavlinkCommandSender::Result result, float) {
×
518
            command_result_callback(result, callback);
×
519
        });
×
520
}
×
521

522
void ActionImpl::set_actuator_async(
×
523
    const int index, const float value, const Action::ResultCallback& callback)
524
{
525
    MavlinkCommandSender::CommandLong command{};
×
526
    command.target_component_id = _system_impl->get_autopilot_id();
×
527

528
    if (_system_impl->autopilot() == Autopilot::ArduPilot) {
×
529
        command.command = MAV_CMD_DO_SET_SERVO;
×
530
        command.params.maybe_param1 = static_cast<float>(index);
×
531
        command.params.maybe_param2 = value;
×
532
    } else {
533
        auto zero_based_index = index - 1;
×
534
        if (zero_based_index >= 0) {
×
535
            command.command = MAV_CMD_DO_SET_ACTUATOR;
×
536
            switch (zero_based_index % 6) {
×
537
                case 0:
×
538
                    command.params.maybe_param1 = value;
×
539
                    break;
×
540
                case 1:
×
541
                    command.params.maybe_param2 = value;
×
542
                    break;
×
543
                case 2:
×
544
                    command.params.maybe_param3 = value;
×
545
                    break;
×
546
                case 3:
×
547
                    command.params.maybe_param4 = value;
×
548
                    break;
×
549
                case 4:
×
550
                    command.params.maybe_param5 = value;
×
551
                    break;
×
552
                case 5:
×
553
                    command.params.maybe_param6 = value;
×
554
                    break;
×
555
            }
556
            command.params.maybe_param7 = static_cast<float>(zero_based_index) / 6.0f;
×
557
        }
558
    }
559

560
    _system_impl->send_command_async(
×
561
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
562
            command_result_callback(result, callback);
×
563
        });
×
564
}
×
565

566
void ActionImpl::transition_to_fixedwing_async(const Action::ResultCallback& callback) const
×
567
{
568
    if (!_vtol_transition_support_known) {
×
569
        if (callback) {
×
570
            callback(Action::Result::VtolTransitionSupportUnknown);
×
571
        }
572
        return;
×
573
    }
574

575
    if (!_vtol_transition_possible) {
×
576
        if (callback) {
×
577
            callback(Action::Result::NoVtolTransitionSupport);
×
578
        }
579
        return;
×
580
    }
581

582
    MavlinkCommandSender::CommandLong command{};
×
583

584
    command.command = MAV_CMD_DO_VTOL_TRANSITION;
×
585
    command.params.maybe_param1 = static_cast<float>(MAV_VTOL_STATE_FW);
×
586
    command.target_component_id = _system_impl->get_autopilot_id();
×
587

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

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

603
    if (!_vtol_transition_possible) {
×
604
        if (callback) {
×
605
            callback(Action::Result::NoVtolTransitionSupport);
×
606
        }
607
        return;
×
608
    }
609
    MavlinkCommandSender::CommandLong command{};
×
610

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

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

621
void ActionImpl::process_extended_sys_state(const mavlink_message_t& message)
×
622
{
623
    mavlink_extended_sys_state_t extended_sys_state;
×
624
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
625

626
    if (extended_sys_state.vtol_state != MAV_VTOL_STATE_UNDEFINED) {
×
627
        _vtol_transition_possible = true;
×
628
    } else {
629
        _vtol_transition_possible = false;
×
630
    }
631
    _vtol_transition_support_known = true;
×
632
}
×
633

634
void ActionImpl::set_takeoff_altitude_async(
×
635
    const float relative_altitude_m, const Action::ResultCallback& callback)
636
{
637
    callback(set_takeoff_altitude(relative_altitude_m));
×
638
}
×
639

640
Action::Result ActionImpl::set_takeoff_altitude(float relative_altitude_m)
×
641
{
642
    if (_system_impl->autopilot() == Autopilot::Px4) {
×
643
        return set_takeoff_altitude_px4(relative_altitude_m);
×
644
    } else {
645
        return set_takeoff_altitude_apm(relative_altitude_m);
×
646
    }
647
}
648

649
Action::Result ActionImpl::set_takeoff_altitude_px4(float relative_altitude_m)
×
650
{
651
    _takeoff_altitude = relative_altitude_m;
×
652

653
    const MavlinkParameterClient::Result result =
654
        _system_impl->set_param_float(TAKEOFF_ALT_PARAM, relative_altitude_m);
×
655
    return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
656
                                                                 Action::Result::ParameterError;
×
657
}
658

659
Action::Result ActionImpl::set_takeoff_altitude_apm(float relative_altitude_m)
×
660
{
661
    _takeoff_altitude = relative_altitude_m;
×
662
    return Action::Result::Success;
×
663
}
664

665
void ActionImpl::get_takeoff_altitude_async(
×
666
    const Action::GetTakeoffAltitudeCallback& callback) const
667
{
668
    auto altitude_result = get_takeoff_altitude();
×
669
    callback(altitude_result.first, altitude_result.second);
×
670
}
×
671

672
std::pair<Action::Result, float> ActionImpl::get_takeoff_altitude() const
×
673
{
674
    if (_system_impl->autopilot() == Autopilot::ArduPilot) {
×
675
        return std::make_pair<>(Action::Result::Success, _takeoff_altitude);
×
676
    } else {
677
        auto result = _system_impl->get_param_float(TAKEOFF_ALT_PARAM);
×
678
        return std::make_pair<>(
679
            (result.first == MavlinkParameterClient::Result::Success) ?
×
680
                Action::Result::Success :
681
                Action::Result::ParameterError,
682
            result.second);
×
683
    }
684
}
685

686
void ActionImpl::set_maximum_speed_async(
×
687
    const float speed_m_s, const Action::ResultCallback& callback) const
688
{
689
    callback(set_maximum_speed(speed_m_s));
×
690
}
×
691

692
Action::Result ActionImpl::set_maximum_speed(float speed_m_s) const
×
693
{
694
    const MavlinkParameterClient::Result result =
695
        _system_impl->set_param_float(MAX_SPEED_PARAM, speed_m_s);
×
696
    return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
697
                                                                 Action::Result::ParameterError;
×
698
}
699

700
void ActionImpl::get_maximum_speed_async(const Action::GetMaximumSpeedCallback& callback) const
×
701
{
702
    auto speed_result = get_maximum_speed();
×
703
    callback(speed_result.first, speed_result.second);
×
704
}
×
705

706
std::pair<Action::Result, float> ActionImpl::get_maximum_speed() const
×
707
{
708
    auto result = _system_impl->get_param_float(MAX_SPEED_PARAM);
×
709
    return std::make_pair<>(
710
        (result.first == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
×
711
                                                                    Action::Result::ParameterError,
712
        result.second);
×
713
}
714

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

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

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

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

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

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

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

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

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

769
    return fut.get();
×
770
}
771

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

798
void ActionImpl::command_result_callback(
4✔
799
    MavlinkCommandSender::Result command_result, const Action::ResultCallback& callback) const
800
{
801
    Action::Result action_result = action_result_from_command_result(command_result);
4✔
802

803
    if (callback) {
4✔
804
        auto temp_callback = callback;
8✔
805
        _system_impl->call_user_callback(
8✔
806
            [temp_callback, action_result]() { temp_callback(action_result); });
807
    }
808
}
4✔
809

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