forked from mavlink/MAVSDK
-
Notifications
You must be signed in to change notification settings - Fork 0
/
action.h
279 lines (248 loc) · 9.48 KB
/
action.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
#pragma once
#include <functional>
namespace dronecore {
class ActionImpl;
/**
* @brief The Action class enables simple actions for a drone
* such as arming, taking off, and landing.
*
* Synchronous and asynchronous variants of the action methods are supplied.
*
* The action methods send their associated MAVLink commands to the vehicle and complete
* (return synchronously or callback asynchronously) with an Action::Result value
* indicating whether the vehicle has accepted or rejected the command, or that there has been some
* error.
* If the command is accepted, the vehicle will then start to perform the associated action.
*/
class Action
{
public:
/**
* @brief Constructor (internal use only).
*
* @param impl Private internal implementation.
*/
explicit Action(ActionImpl *impl);
/**
* @brief Destructor (internal use only).
*/
~Action();
/**
* @brief Possible results returned for commanded actions.
*/
enum class Result {
SUCCESS = 0, /**< @brief Success. The action command was accepted by the vehicle. */
NO_DEVICE, /**< @brief No device is connected error. */
CONNECTION_ERROR, /**< @brief %Connection error. */
BUSY, /**< @brief Vehicle busy error. */
COMMAND_DENIED, /**< @brief Command refused by vehicle. */
COMMAND_DENIED_LANDED_STATE_UNKNOWN, /**< @brief Command refused because landed state is unknown. */
COMMAND_DENIED_NOT_LANDED, /**< @brief Command refused because vehicle not landed. */
TIMEOUT, /**< @brief Timeout waiting for command acknowledgement from vehicle. */
VTOL_TRANSITION_SUPPORT_UNKNOWN, /**< @brief hybrid/VTOL transition refused because VTOL support is unknown. */
NO_VTOL_TRANSITION_SUPPORT, /**< @brief Vehicle does not support hybrid/VTOL transitions. */
UNKNOWN /**< @brief Unspecified error. */
};
/**
* @brief Returns a human-readable English string for an Action::Result.
*
* @param result The enum value for which a human readable string is required.
* @return Human readable string for the Action::Result.
*/
static const char *result_str(Result result);
/**
* @brief Send command to *arm* the drone (synchronous).
*
* **Note** Arming a drone normally causes motors to spin at idle.
* Before arming take all safety precautions and stand clear of the drone!
*
* @return Result of request.
*/
Result arm() const;
/**
* @brief Send command to *disarm* the drone (synchronous).
*
* This will disarm a drone that considers itself landed. If flying, the drone should
* reject the disarm command. Disarming means that all motors will stop.
*
* @return Result of request.
*/
Result disarm() const;
/**
* @brief Send command to *kill* the drone (synchronous).
*
* This will disarm a drone irrespective of whether it is landed or flying.
* Note that the drone will fall out of the sky if this command is used while flying.
*
* @return Result of request.
*/
Result kill() const;
/**
* @brief Send command to *take off and hover* (synchronous).
*
* This switches the drone into position control mode and commands it to take off and hover at
* the takeoff altitude (set using set_takeoff_altitude()).
*
* Note that the vehicle must be armed before it can take off.
*
* @return Result of request.
*/
Result takeoff() const;
/**
* @brief Send command to *land* at the current position (synchronous).
*
* This switches the drone to
* [Land mode](https://docs.px4.io/en/flight_modes/land.html).
*
* @return Result of request.
*/
Result land() const;
/**
* @brief Send command to *return to the launch* (takeoff) position and *land* (asynchronous).
*
* This switches the drone into [RTL mode](https://docs.px4.io/en/flight_modes/rtl.html) which
* generally means it will rise up to a certain altitude to clear any obstacles before heading
* back to the launch (takeoff) position and land there.
*
* @return Result of request.
*/
Result return_to_launch() const;
/**
* @brief Send command to transition the drone to fixedwing.
*
* The associated action will only be executed for VTOL vehicles (on other vehicle types the
* command will fail with a Result). The command will succeed if called when the vehicle is
* already in fixedwing mode.
*
* @return Result of request.
*/
Result transition_to_fixedwing() const;
/**
* @brief Send command to transition the drone to multicopter.
*
* The associated action will only be executed for VTOL vehicles (on other vehicle types the
* command will fail with a Result). The command will succeed if called when the vehicle is
* already in multicopter mode.
*
* @return Result of request.
*/
Result transition_to_multicopter() const;
/**
* @brief Callback type for asynchronous Action calls.
*/
typedef std::function<void(Result)> result_callback_t;
/**
* @brief Send command to *arm* the drone (asynchronous).
*
* Note that arming a drone normally means that the motors will spin at idle.
* Therefore, before arming take all safety precautions and stand clear of the drone.
*
* @param callback Function to call with result of request.
*/
void arm_async(result_callback_t callback);
/**
* @brief Send command to *disarm* the drone (asynchronous).
*
* This will disarm a drone that considers itself landed. If flying, the drone should
* reject the disarm command. Disarming means that all motors will stop.
*
* @param callback Function to call with result of request.
*/
void disarm_async(result_callback_t callback);
/**
* @brief Send command to *kill* the drone (asynchronous).
*
* This will disarm a drone irrespective of whether it is landed or flying.
* Note that the drone will fall out of the sky if you use this command while flying.
*
* @param callback Function to call with result of request.
*/
void kill_async(result_callback_t callback);
/**
* @brief Send command to *take off and hover* (asynchronous).
*
* This switches the drone into position control mode and commands it to take off and hover at
* the takeoff altitude set using set_takeoff_altitude().
*
* Note that the vehicle must be armed before it can take off.
*
* @param callback Function to call with result of request
*/
void takeoff_async(result_callback_t callback);
/**
* @brief Send command to *land* at the current position (asynchronous).
*
* This switches the drone to
* [Land mode](https://docs.px4.io/en/flight_modes/land.html).
*
* @param callback Function to call with result of request.
*/
void land_async(result_callback_t callback);
/**
* @brief Send command to *return to the launch* (takeoff) position and *land* (asynchronous).
*
* This switches the drone into [RTL mode](https://docs.px4.io/en/flight_modes/rtl.html) which
* generally means it will rise up to a certain altitude to clear any obstacles before heading
* back to the launch (takeoff) position and land there.
*
* @param callback Function to call with result of request.
*/
void return_to_launch_async(result_callback_t callback);
/**
* @brief Send command to transition the drone to fixedwing (asynchronous).
*
* The associated action will only be executed for VTOL vehicles (on other vehicle types the
* command will fail with a Result). The command will succeed if called when the vehicle is
* already in fixedwing mode.
*
* @param callback Function to call with result of request.
*/
void transition_to_fixedwing_async(result_callback_t callback);
/**
* @brief Send command to transition the drone to multicopter (asynchronous).
*
* The associated action will only be executed for VTOL vehicles (on other vehicle types the
* command will fail with a Result). The command will succeed if called when the vehicle is
* already in multicopter mode.
*
* @param callback Function to call with result of request.
*/
void transition_to_multicopter_async(result_callback_t callback);
/**
* @brief Set takeoff altitude above ground.
*
* @param relative_altitude_m Takeoff altitude relative to takeoff location, in meters.
*/
void set_takeoff_altitude(float relative_altitude_m);
/**
* @brief Get the takeoff altitude.
*
* @return takeoff Takeoff altitude relative to ground/takeoff location, in meters.
*/
float get_takeoff_altitude_m() const;
/**
* @brief Set vehicle maximum speed.
*
* @param speed_m_s Maximum speed in metres/second.
*/
void set_max_speed(float speed_m_s);
/**
* @brief Get the vehicle maximum speed.
*
* @return Maximum speed in metres/second.
*/
float get_max_speed_m_s() const;
// Non-copyable
/**
* @brief Copy constructor (object is not copyable).
*/
Action(const Action &) = delete;
/**
* @brief Equality operator (object is not copyable).
*/
const Action &operator=(const Action &) = delete;
private:
/** @private Underlying implementation, set at instantiation */
ActionImpl *_impl;
};
} // namespace dronecore