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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

25.56
/src/mavsdk/plugins/action_server/action_server_impl.cpp
1
#include "action_server_impl.h"
2
#include "unused.h"
3
#include "flight_mode.h"
4
#include "callback_list.tpp"
5

6
namespace mavsdk {
7

8
template class CallbackList<ActionServer::Result, ActionServer::ArmDisarm>;
9
template class CallbackList<ActionServer::Result, ActionServer::FlightMode>;
10
template class CallbackList<ActionServer::Result, bool>;
11

12
ActionServer::FlightMode telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
×
13
{
14
    switch (flight_mode) {
×
15
        case FlightMode::Ready:
×
16
            return ActionServer::FlightMode::Ready;
×
17
        case FlightMode::Takeoff:
×
18
            return ActionServer::FlightMode::Takeoff;
×
19
        case FlightMode::Hold:
×
20
            return ActionServer::FlightMode::Hold;
×
21
        case FlightMode::Mission:
×
22
            return ActionServer::FlightMode::Mission;
×
23
        case FlightMode::ReturnToLaunch:
×
24
            return ActionServer::FlightMode::ReturnToLaunch;
×
25
        case FlightMode::Land:
×
26
            return ActionServer::FlightMode::Land;
×
27
        case FlightMode::Offboard:
×
28
            return ActionServer::FlightMode::Offboard;
×
29
        case FlightMode::FollowMe:
×
30
            return ActionServer::FlightMode::FollowMe;
×
31
        case FlightMode::Manual:
×
32
            return ActionServer::FlightMode::Manual;
×
33
        case FlightMode::Posctl:
×
34
            return ActionServer::FlightMode::Posctl;
×
35
        case FlightMode::Altctl:
×
36
            return ActionServer::FlightMode::Altctl;
×
37
        case FlightMode::Acro:
×
38
            return ActionServer::FlightMode::Acro;
×
39
        case FlightMode::Stabilized:
×
40
            return ActionServer::FlightMode::Stabilized;
×
41
        default:
×
42
            return ActionServer::FlightMode::Unknown;
×
43
    }
44
}
45

46
ActionServerImpl::ActionServerImpl(std::shared_ptr<ServerComponent> server_component) :
1✔
47
    ServerPluginImplBase(server_component)
1✔
48
{
49
    _server_component_impl->register_plugin(this);
1✔
50
}
1✔
51

52
ActionServerImpl::~ActionServerImpl()
2✔
53
{
54
    _server_component_impl->unregister_plugin(this);
1✔
55
}
2✔
56

57
void ActionServerImpl::init()
1✔
58
{
59
    _send_version_cookie = _server_component_impl->add_call_every(
1✔
60
        [this]() { _server_component_impl->send_autopilot_version(); }, 1.0);
2✔
61

62
    // Arming / Disarm / Kill
63
    _server_component_impl->register_mavlink_command_handler(
1✔
64
        MAV_CMD_COMPONENT_ARM_DISARM,
65
        [this](const MavlinkCommandReceiver::CommandLong& command) {
26✔
66
            ActionServer::ArmDisarm armDisarm{
4✔
67
                command.params.param1 == 1, command.params.param2 == 21196};
4✔
68

69
            std::lock_guard<std::mutex> lock(_callback_mutex);
4✔
70

71
            // Check arm states - Ugly.
72
            auto request_ack = MAV_RESULT_UNSUPPORTED;
4✔
73
            bool force = armDisarm.force;
4✔
74
            if (armDisarm.arm) {
4✔
75
                request_ack = (_armable || (force && _force_armable)) ?
2✔
76
                                  MAV_RESULT::MAV_RESULT_ACCEPTED :
77
                                  MAV_RESULT_TEMPORARILY_REJECTED;
78
            } else {
79
                request_ack = (_disarmable || (force && _force_disarmable)) ?
2✔
80
                                  MAV_RESULT::MAV_RESULT_ACCEPTED :
81
                                  MAV_RESULT_TEMPORARILY_REJECTED;
82
            }
83

84
            if (request_ack == MAV_RESULT::MAV_RESULT_ACCEPTED) {
4✔
85
                set_server_armed(armDisarm.arm);
2✔
86
            }
87

88
            auto result = (request_ack == MAV_RESULT::MAV_RESULT_ACCEPTED) ?
4✔
89
                              ActionServer::Result::Success :
90
                              ActionServer::Result::CommandDenied;
91

92
            _arm_disarm_callbacks.queue(result, armDisarm, [this](const auto& func) {
4✔
93
                _server_component_impl->call_user_callback(func);
×
94
            });
×
95

96
            return _server_component_impl->make_command_ack_message(command, request_ack);
4✔
97
        },
4✔
98
        this);
99

100
    _server_component_impl->register_mavlink_command_handler(
1✔
101
        MAV_CMD_NAV_TAKEOFF,
102
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
103
            std::lock_guard<std::mutex> lock(_callback_mutex);
×
104

105
            if (_allow_takeoff) {
×
106
                _takeoff_callbacks.queue(
×
107
                    ActionServer::Result::Success, true, [this](const auto& func) {
×
108
                        _server_component_impl->call_user_callback(func);
×
109
                    });
×
110

111
                return _server_component_impl->make_command_ack_message(
×
112
                    command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
113
            } else {
114
                _takeoff_callbacks.queue(
×
115
                    ActionServer::Result::CommandDenied, false, [this](const auto& func) {
×
116
                        _server_component_impl->call_user_callback(func);
×
117
                    });
×
118

119
                return _server_component_impl->make_command_ack_message(
×
120
                    command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
121
            }
122
        },
×
123
        this);
124

125
    // Flight mode
126
    _server_component_impl->register_mavlink_command_handler(
1✔
127
        MAV_CMD_DO_SET_MODE,
128
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
129
            auto base_mode = static_cast<uint8_t>(command.params.param1);
×
130
            auto is_custom = (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) ==
×
131
                             MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
132
            ActionServer::FlightMode request_flight_mode = ActionServer::FlightMode::Unknown;
×
133

134
            auto custom_mode = static_cast<uint8_t>(command.params.param2);
×
135
            auto sub_custom_mode = static_cast<uint8_t>(command.params.param3);
×
136

137
            std::lock_guard<std::mutex> lock(_callback_mutex);
×
138

139
            if (is_custom) {
×
140
                // PX4 uses custom modes
141
                px4_custom_mode px4_mode{};
×
142
                px4_mode.main_mode = custom_mode;
×
143
                px4_mode.sub_mode = sub_custom_mode;
×
144
                auto system_flight_mode = to_flight_mode_from_px4_mode(px4_mode.data);
×
145
                request_flight_mode = telemetry_flight_mode_from_flight_mode(system_flight_mode);
×
146
            } else {
147
                // TO DO: non PX4 flight modes...
148
                // Just bug out now if not using PX4 modes
149
                _flight_mode_change_callbacks.queue(
×
150
                    ActionServer::Result::ParameterError,
151
                    request_flight_mode,
152
                    [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
153

154
                return _server_component_impl->make_command_ack_message(
×
155
                    command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
156
            }
157

158
            bool allow_mode = false;
×
159
            switch (request_flight_mode) {
×
160
                case ActionServer::FlightMode::Manual:
×
161
                    allow_mode = true;
×
162
                    break;
×
163
                case ActionServer::FlightMode::Mission:
×
164
                    allow_mode = _allowed_flight_modes.can_auto_mode;
×
165
                    break;
×
166
                case ActionServer::FlightMode::Stabilized:
×
167
                    allow_mode = _allowed_flight_modes.can_stabilize_mode;
×
168
                    break;
×
169
                case ActionServer::FlightMode::Offboard:
×
170
                    allow_mode = _allowed_flight_modes.can_guided_mode;
×
171
                    break;
×
172
                default:
×
173
                    allow_mode = false;
×
174
                    break;
×
175
            }
176

177
            // PX4...
178
            px4_custom_mode px4_mode{};
×
179
            px4_mode.data = get_custom_mode();
×
180

181
            if (allow_mode) {
×
182
                px4_mode.main_mode = custom_mode;
×
183
                px4_mode.sub_mode = sub_custom_mode;
×
184
                set_custom_mode(px4_mode.data);
×
185
            }
186

187
            _flight_mode_change_callbacks.queue(
×
188
                allow_mode ? ActionServer::Result::Success : ActionServer::Result::CommandDenied,
189
                request_flight_mode,
190
                [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
191

192
            return _server_component_impl->make_command_ack_message(
×
193
                command,
194
                allow_mode ? MAV_RESULT::MAV_RESULT_ACCEPTED : MAV_RESULT_TEMPORARILY_REJECTED);
×
195
        },
×
196
        this);
197
}
1✔
198

199
void ActionServerImpl::deinit()
1✔
200
{
201
    _server_component_impl->unregister_all_mavlink_command_handlers(this);
1✔
202
    _server_component_impl->remove_call_every(_send_version_cookie);
1✔
203
}
1✔
204

205
ActionServer::ArmDisarmHandle
206
ActionServerImpl::subscribe_arm_disarm(const ActionServer::ArmDisarmCallback& callback)
×
207
{
208
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
209
    return _arm_disarm_callbacks.subscribe(callback);
×
210
}
×
211

212
void ActionServerImpl::unsubscribe_arm_disarm(ActionServer::ArmDisarmHandle handle)
×
213
{
214
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
215
    _arm_disarm_callbacks.unsubscribe(handle);
×
216
}
×
217

218
ActionServer::FlightModeChangeHandle ActionServerImpl::subscribe_flight_mode_change(
×
219
    const ActionServer::FlightModeChangeCallback& callback)
220
{
221
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
222
    return _flight_mode_change_callbacks.subscribe(callback);
×
223
}
×
224

225
void ActionServerImpl::unsubscribe_flight_mode_change(ActionServer::FlightModeChangeHandle handle)
×
226
{
227
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
228
    _flight_mode_change_callbacks.unsubscribe(handle);
×
229
}
×
230

231
ActionServer::TakeoffHandle
232
ActionServerImpl::subscribe_takeoff(const ActionServer::TakeoffCallback& callback)
×
233
{
234
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
235
    return _takeoff_callbacks.subscribe(callback);
×
236
}
×
237

238
void ActionServerImpl::unsubscribe_takeoff(ActionServer::TakeoffHandle handle)
×
239
{
240
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
241
    _takeoff_callbacks.unsubscribe(handle);
×
242
}
×
243

244
ActionServer::LandHandle
245
ActionServerImpl::subscribe_land(const ActionServer::LandCallback& callback)
×
246
{
247
    // TODO: implement
248
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
249
    return _land_callbacks.subscribe(callback);
×
250
}
×
251

252
void ActionServerImpl::unsubscribe_land(ActionServer::LandHandle handle)
×
253
{
254
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
255
    _land_callbacks.unsubscribe(handle);
×
256
}
×
257

258
ActionServer::RebootHandle
259
ActionServerImpl::subscribe_reboot(const ActionServer::RebootCallback& callback)
×
260
{
261
    // TODO: implement
262
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
263
    return _reboot_callbacks.subscribe(callback);
×
264
}
×
265

266
void ActionServerImpl::unsubscribe_reboot(ActionServer::RebootHandle handle)
×
267
{
268
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
269
    _reboot_callbacks.unsubscribe(handle);
×
270
}
×
271

272
ActionServer::ShutdownHandle
273
ActionServerImpl::subscribe_shutdown(const ActionServer::ShutdownCallback& callback)
×
274
{
275
    // TODO: implement
276
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
277
    return _shutdown_callbacks.subscribe(callback);
×
278
}
×
279

280
void ActionServerImpl::unsubscribe_shutdown(ActionServer::ShutdownHandle handle)
×
281
{
282
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
283
    _shutdown_callbacks.unsubscribe(handle);
×
284
}
×
285

286
ActionServer::TerminateHandle
287
ActionServerImpl::subscribe_terminate(const ActionServer::TerminateCallback& callback)
×
288
{
289
    // TODO: implement
290
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
291
    return _terminate_callbacks.subscribe(callback);
×
292
}
×
293

294
void ActionServerImpl::unsubscribe_terminate(ActionServer::TerminateHandle handle)
×
295
{
296
    std::lock_guard<std::mutex> lock(_callback_mutex);
×
297
    _terminate_callbacks.unsubscribe(handle);
×
298
}
×
299

300
ActionServer::Result ActionServerImpl::set_allow_takeoff(bool allow_takeoff)
×
301
{
302
    _allow_takeoff = allow_takeoff;
×
303
    return ActionServer::Result::Success;
×
304
}
305

306
ActionServer::Result ActionServerImpl::set_armable(bool armable, bool force_armable)
1✔
307
{
308
    std::lock_guard<std::mutex> lock(_flight_mode_mutex);
1✔
309
    _armable = armable;
1✔
310
    _force_armable = force_armable;
1✔
311
    return ActionServer::Result::Success;
2✔
312
}
1✔
313

314
ActionServer::Result ActionServerImpl::set_disarmable(bool disarmable, bool force_disarmable)
1✔
315
{
316
    std::lock_guard<std::mutex> lock(_flight_mode_mutex);
1✔
317
    _disarmable = disarmable;
1✔
318
    _force_disarmable = force_disarmable;
1✔
319
    return ActionServer::Result::Success;
2✔
320
}
1✔
321

322
ActionServer::Result
323
ActionServerImpl::set_allowable_flight_modes(ActionServer::AllowableFlightModes flight_modes)
×
324
{
325
    std::lock_guard<std::mutex> lock(_flight_mode_mutex);
×
326
    _allowed_flight_modes = flight_modes;
×
327
    return ActionServer::Result::Success;
×
328
}
×
329

330
ActionServer::AllowableFlightModes ActionServerImpl::get_allowable_flight_modes()
×
331
{
332
    std::lock_guard<std::mutex> lock(_flight_mode_mutex);
×
333
    return _allowed_flight_modes;
×
334
}
×
335

336
void ActionServerImpl::set_base_mode(uint8_t base_mode)
2✔
337
{
338
    _server_component_impl->set_base_mode(base_mode);
2✔
339
}
2✔
340

341
uint8_t ActionServerImpl::get_base_mode() const
2✔
342
{
343
    return _server_component_impl->get_base_mode();
2✔
344
}
345

346
void ActionServerImpl::set_custom_mode(uint32_t custom_mode)
×
347
{
348
    _server_component_impl->set_custom_mode(custom_mode);
×
349
}
×
350

351
uint32_t ActionServerImpl::get_custom_mode() const
×
352
{
353
    return _server_component_impl->get_custom_mode();
×
354
}
355

356
void ActionServerImpl::set_server_armed(bool armed)
2✔
357
{
358
    uint8_t base_mode = get_base_mode();
2✔
359
    if (armed) {
2✔
360
        base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
1✔
361
    } else {
362
        base_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
1✔
363
    }
364
    set_base_mode(base_mode);
2✔
365
}
2✔
366

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