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

mavlink / MAVSDK / 4899817366

pending completion
4899817366

Pull #1772

github

GitHub
Merge c0bb90862 into e4e9c71dd
Pull Request #1772: Refactor MAVLinkParameters into client and server classes

2192 of 2192 new or added lines in 34 files covered. (100.0%)

7708 of 24812 relevant lines covered (31.07%)

19.96 hits per line

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

14.97
/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() == SystemImpl::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() == SystemImpl::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.params.maybe_param4 = static_cast<float>(to_rad_from_deg(yaw_deg));
×
454
            command.params.x = int32_t(std::round(latitude_deg * 1e7));
×
455
            command.params.y = int32_t(std::round(longitude_deg * 1e7));
×
456
            command.params.maybe_z = altitude_amsl_m;
×
457

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

464
    // Change to Hold mode first
465
    if (_system_impl->get_flight_mode() != FlightMode::Hold) {
×
466
        _system_impl->set_flight_mode_async(
×
467
            FlightMode::Hold,
468
            [this, callback, send_do_reposition](MavlinkCommandSender::Result result, float) {
×
469
                Action::Result action_result = action_result_from_command_result(result);
×
470
                if (action_result != Action::Result::Success) {
×
471
                    command_result_callback(result, callback);
×
472
                    return;
×
473
                }
474
                send_do_reposition();
×
475
            });
476
        return;
×
477
    }
478

479
    send_do_reposition();
×
480
}
481

482
void ActionImpl::do_orbit_async(
×
483
    const float radius_m,
484
    const float velocity_ms,
485
    const Action::OrbitYawBehavior yaw_behavior,
486
    const double latitude_deg,
487
    const double longitude_deg,
488
    const double absolute_altitude_m,
489
    const Action::ResultCallback& callback)
490
{
491
    MavlinkCommandSender::CommandInt command{};
×
492

493
    command.command = MAV_CMD_DO_ORBIT;
×
494
    command.target_component_id = _system_impl->get_autopilot_id();
×
495
    command.params.maybe_param1 = radius_m;
×
496
    command.params.maybe_param2 = velocity_ms;
×
497
    command.params.maybe_param3 = static_cast<float>(yaw_behavior);
×
498
    command.params.x = int32_t(std::round(latitude_deg * 1e7));
×
499
    command.params.y = int32_t(std::round(longitude_deg * 1e7));
×
500
    command.params.maybe_z = static_cast<float>(absolute_altitude_m);
×
501

502
    _system_impl->send_command_async(
×
503
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
504
            command_result_callback(result, callback);
×
505
        });
×
506
}
×
507

508
void ActionImpl::hold_async(const Action::ResultCallback& callback) const
×
509
{
510
    _system_impl->set_flight_mode_async(
×
511
        FlightMode::Hold, [this, callback](MavlinkCommandSender::Result result, float) {
×
512
            command_result_callback(result, callback);
×
513
        });
×
514
}
×
515

516
void ActionImpl::set_actuator_async(
×
517
    const int index, const float value, const Action::ResultCallback& callback)
518
{
519
    MavlinkCommandSender::CommandLong command{};
×
520

521
    command.command = MAV_CMD_DO_SET_ACTUATOR;
×
522
    command.target_component_id = _system_impl->get_autopilot_id();
×
523

524
    switch (index % 6) {
×
525
        case 1:
×
526
            command.params.maybe_param1 = value;
×
527
            break;
×
528
        case 2:
×
529
            command.params.maybe_param2 = value;
×
530
            break;
×
531
        case 3:
×
532
            command.params.maybe_param3 = value;
×
533
            break;
×
534
        case 4:
×
535
            command.params.maybe_param4 = value;
×
536
            break;
×
537
        case 5:
×
538
            command.params.maybe_param5 = value;
×
539
            break;
×
540
        case 6:
×
541
            command.params.maybe_param6 = value;
×
542
            break;
×
543
    }
544
    command.params.maybe_param7 = static_cast<float>(index) / 6.0f;
×
545

546
    _system_impl->send_command_async(
×
547
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
548
            command_result_callback(result, callback);
×
549
        });
×
550
}
×
551

552
void ActionImpl::transition_to_fixedwing_async(const Action::ResultCallback& callback) const
×
553
{
554
    if (!_vtol_transition_support_known) {
×
555
        if (callback) {
×
556
            callback(Action::Result::VtolTransitionSupportUnknown);
×
557
        }
558
        return;
×
559
    }
560

561
    if (!_vtol_transition_possible) {
×
562
        if (callback) {
×
563
            callback(Action::Result::NoVtolTransitionSupport);
×
564
        }
565
        return;
×
566
    }
567

568
    MavlinkCommandSender::CommandLong command{};
×
569

570
    command.command = MAV_CMD_DO_VTOL_TRANSITION;
×
571
    command.params.maybe_param1 = static_cast<float>(MAV_VTOL_STATE_FW);
×
572
    command.target_component_id = _system_impl->get_autopilot_id();
×
573

574
    _system_impl->send_command_async(
×
575
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
576
            command_result_callback(result, callback);
×
577
        });
×
578
}
579

580
void ActionImpl::transition_to_multicopter_async(const Action::ResultCallback& callback) const
×
581
{
582
    if (!_vtol_transition_support_known) {
×
583
        if (callback) {
×
584
            callback(Action::Result::VtolTransitionSupportUnknown);
×
585
        }
586
        return;
×
587
    }
588

589
    if (!_vtol_transition_possible) {
×
590
        if (callback) {
×
591
            callback(Action::Result::NoVtolTransitionSupport);
×
592
        }
593
        return;
×
594
    }
595
    MavlinkCommandSender::CommandLong command{};
×
596

597
    command.command = MAV_CMD_DO_VTOL_TRANSITION;
×
598
    command.params.maybe_param1 = static_cast<float>(MAV_VTOL_STATE_MC);
×
599
    command.target_component_id = _system_impl->get_autopilot_id();
×
600

601
    _system_impl->send_command_async(
×
602
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
603
            command_result_callback(result, callback);
×
604
        });
×
605
}
606

607
void ActionImpl::process_extended_sys_state(const mavlink_message_t& message)
×
608
{
609
    mavlink_extended_sys_state_t extended_sys_state;
×
610
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
611

612
    if (extended_sys_state.vtol_state != MAV_VTOL_STATE_UNDEFINED) {
×
613
        _vtol_transition_possible = true;
×
614
    } else {
615
        _vtol_transition_possible = false;
×
616
    }
617
    _vtol_transition_support_known = true;
×
618
}
×
619

620
void ActionImpl::set_takeoff_altitude_async(
×
621
    const float relative_altitude_m, const Action::ResultCallback& callback)
622
{
623
    callback(set_takeoff_altitude(relative_altitude_m));
×
624
}
×
625

626
Action::Result ActionImpl::set_takeoff_altitude(float relative_altitude_m)
×
627
{
628
    if (_system_impl->autopilot() == SystemImpl::Autopilot::Px4) {
×
629
        return set_takeoff_altitude_px4(relative_altitude_m);
×
630
    } else {
631
        return set_takeoff_altitude_apm(relative_altitude_m);
×
632
    }
633
}
634

635
Action::Result ActionImpl::set_takeoff_altitude_px4(float relative_altitude_m)
×
636
{
637
    _takeoff_altitude = relative_altitude_m;
×
638

639
    const MavlinkParameterSender::Result result =
640
        _system_impl->set_param_float(TAKEOFF_ALT_PARAM, relative_altitude_m);
×
641
    return (result == MavlinkParameterSender::Result::Success) ? Action::Result::Success :
×
642
                                                                 Action::Result::ParameterError;
×
643
}
644

645
Action::Result ActionImpl::set_takeoff_altitude_apm(float relative_altitude_m)
×
646
{
647
    _takeoff_altitude = relative_altitude_m;
×
648
    return Action::Result::Success;
×
649
}
650

651
void ActionImpl::get_takeoff_altitude_async(
×
652
    const Action::GetTakeoffAltitudeCallback& callback) const
653
{
654
    auto altitude_result = get_takeoff_altitude();
×
655
    callback(altitude_result.first, altitude_result.second);
×
656
}
×
657

658
std::pair<Action::Result, float> ActionImpl::get_takeoff_altitude() const
×
659
{
660
    if (_system_impl->autopilot() == SystemImpl::Autopilot::ArduPilot) {
×
661
        return std::make_pair<>(Action::Result::Success, _takeoff_altitude);
×
662
    } else {
663
        auto result = _system_impl->get_param_float(TAKEOFF_ALT_PARAM);
×
664
        return std::make_pair<>(
665
            (result.first == MavlinkParameterSender::Result::Success) ?
×
666
                Action::Result::Success :
667
                Action::Result::ParameterError,
668
            result.second);
×
669
    }
670
}
671

672
void ActionImpl::set_maximum_speed_async(
×
673
    const float speed_m_s, const Action::ResultCallback& callback) const
674
{
675
    callback(set_maximum_speed(speed_m_s));
×
676
}
×
677

678
Action::Result ActionImpl::set_maximum_speed(float speed_m_s) const
×
679
{
680
    const MavlinkParameterSender::Result result =
681
        _system_impl->set_param_float(MAX_SPEED_PARAM, speed_m_s);
×
682
    return (result == MavlinkParameterSender::Result::Success) ? Action::Result::Success :
×
683
                                                                 Action::Result::ParameterError;
×
684
}
685

686
void ActionImpl::get_maximum_speed_async(const Action::GetMaximumSpeedCallback& callback) const
×
687
{
688
    auto speed_result = get_maximum_speed();
×
689
    callback(speed_result.first, speed_result.second);
×
690
}
×
691

692
std::pair<Action::Result, float> ActionImpl::get_maximum_speed() const
×
693
{
694
    auto result = _system_impl->get_param_float(MAX_SPEED_PARAM);
×
695
    return std::make_pair<>(
696
        (result.first == MavlinkParameterSender::Result::Success) ? Action::Result::Success :
×
697
                                                                    Action::Result::ParameterError,
698
        result.second);
×
699
}
700

701
void ActionImpl::set_return_to_launch_altitude_async(
×
702
    const float relative_altitude_m, const Action::ResultCallback& callback) const
703
{
704
    callback(set_return_to_launch_altitude(relative_altitude_m));
×
705
}
×
706

707
Action::Result ActionImpl::set_return_to_launch_altitude(const float relative_altitude_m) const
×
708
{
709
    const MavlinkParameterSender::Result result =
710
        _system_impl->set_param_float(RTL_RETURN_ALTITUDE_PARAM, relative_altitude_m);
×
711
    return (result == MavlinkParameterSender::Result::Success) ? Action::Result::Success :
×
712
                                                                 Action::Result::ParameterError;
×
713
}
714

715
void ActionImpl::get_return_to_launch_altitude_async(
×
716
    const Action::GetReturnToLaunchAltitudeCallback& callback) const
717
{
718
    const auto get_result = get_return_to_launch_altitude();
×
719
    callback(get_result.first, get_result.second);
×
720
}
×
721

722
std::pair<Action::Result, float> ActionImpl::get_return_to_launch_altitude() const
×
723
{
724
    auto result = _system_impl->get_param_float(RTL_RETURN_ALTITUDE_PARAM);
×
725
    return std::make_pair<>(
726
        (result.first == MavlinkParameterSender::Result::Success) ? Action::Result::Success :
×
727
                                                                    Action::Result::ParameterError,
728
        result.second);
×
729
}
730

731
void ActionImpl::set_current_speed_async(float speed_m_s, const Action::ResultCallback& callback)
×
732
{
733
    MavlinkCommandSender::CommandLong command{};
×
734

735
    command.command = MAV_CMD_DO_CHANGE_SPEED;
×
736
    command.params.maybe_param1 = 1.0f; // ground speed
×
737
    command.params.maybe_param2 = speed_m_s;
×
738
    command.params.maybe_param3 = -1.0f; // no throttle set
×
739
    command.params.maybe_param4 = 0.0f; // reserved
×
740
    command.target_component_id = _system_impl->get_autopilot_id();
×
741

742
    _system_impl->send_command_async(
×
743
        command, [this, callback](MavlinkCommandSender::Result result, float) {
×
744
            command_result_callback(result, callback);
×
745
        });
×
746
}
×
747

748
Action::Result ActionImpl::set_current_speed(float speed_m_s)
×
749
{
750
    auto prom = std::promise<Action::Result>();
×
751
    auto fut = prom.get_future();
×
752

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

755
    return fut.get();
×
756
}
757

758
Action::Result ActionImpl::action_result_from_command_result(MavlinkCommandSender::Result result)
4✔
759
{
760
    switch (result) {
4✔
761
        case MavlinkCommandSender::Result::Success:
2✔
762
            return Action::Result::Success;
2✔
763
        case MavlinkCommandSender::Result::NoSystem:
×
764
            return Action::Result::NoSystem;
×
765
        case MavlinkCommandSender::Result::ConnectionError:
×
766
            return Action::Result::ConnectionError;
×
767
        case MavlinkCommandSender::Result::Busy:
×
768
            return Action::Result::Busy;
×
769
        case MavlinkCommandSender::Result::Denied:
2✔
770
            // Fallthrough
771
        case MavlinkCommandSender::Result::TemporarilyRejected:
772
            return Action::Result::CommandDenied;
2✔
773
        case MavlinkCommandSender::Result::Failed:
×
774
            return Action::Result::Failed;
×
775
        case MavlinkCommandSender::Result::Timeout:
×
776
            return Action::Result::Timeout;
×
777
        case MavlinkCommandSender::Result::Unsupported:
×
778
            return Action::Result::Unsupported;
×
779
        default:
×
780
            return Action::Result::Unknown;
×
781
    }
782
}
783

784
void ActionImpl::command_result_callback(
4✔
785
    MavlinkCommandSender::Result command_result, const Action::ResultCallback& callback) const
786
{
787
    Action::Result action_result = action_result_from_command_result(command_result);
4✔
788

789
    if (callback) {
4✔
790
        auto temp_callback = callback;
8✔
791
        _system_impl->call_user_callback(
8✔
792
            [temp_callback, action_result]() { temp_callback(action_result); });
793
    }
794
}
4✔
795

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