-
Notifications
You must be signed in to change notification settings - Fork 99
/
Copy pathaction.proto
317 lines (289 loc) · 11.4 KB
/
action.proto
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
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
syntax = "proto3";
package mavsdk.rpc.action;
import "mavsdk_options.proto";
option java_package = "io.mavsdk.action";
option java_outer_classname = "ActionProto";
// Enable simple actions such as arming, taking off, and landing.
service ActionService {
/*
* Send command to arm the drone.
*
* Arming a drone normally causes motors to spin at idle.
* Before arming take all safety precautions and stand clear of the drone!
*/
rpc Arm(ArmRequest) returns(ArmResponse) {}
/*
* Send command to force-arm the drone without any checks.
*
* Attention: this is not to be used for normal flying but only bench tests!
*
* Arming a drone normally causes motors to spin at idle.
* Before arming take all safety precautions and stand clear of the drone!
*/
rpc ArmForce(ArmForceRequest) returns(ArmForceResponse) {}
/*
* Send command to disarm the drone.
*
* 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.
*/
rpc Disarm(DisarmRequest) returns(DisarmResponse) {}
/*
* Send command to take off and hover.
*
* This switches the drone into position control mode and commands
* it to take off and hover at the takeoff altitude.
*
* Note that the vehicle must be armed before it can take off.
*/
rpc Takeoff(TakeoffRequest) returns(TakeoffResponse) {}
/*
* Send command to land at the current position.
*
* This switches the drone to 'Land' flight mode.
*/
rpc Land(LandRequest) returns(LandResponse) {}
/*
* Send command to reboot the drone components.
*
* This will reboot the autopilot, companion computer, camera and gimbal.
*/
rpc Reboot(RebootRequest) returns(RebootResponse) {}
/*
* Send command to shut down the drone components.
*
* This will shut down the autopilot, onboard computer, camera and gimbal.
* This command should only be used when the autopilot is disarmed and autopilots commonly
* reject it if they are not already ready to shut down.
*/
rpc Shutdown(ShutdownRequest) returns(ShutdownResponse) {}
/*
* Send command to terminate the drone.
*
* This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute).
*/
rpc Terminate(TerminateRequest) returns(TerminateResponse) {}
/*
* Send command to kill the drone.
*
* 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.
*/
rpc Kill(KillRequest) returns(KillResponse) {}
/*
* Send command to return to the launch (takeoff) position and land.
*
* This switches the drone into [Return mode](https://docs.px4.io/master/en/flight_modes/return.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.
*/
rpc ReturnToLaunch(ReturnToLaunchRequest) returns(ReturnToLaunchResponse) {}
/*
* Send command to move the vehicle to a specific global position.
*
* The latitude and longitude are given in degrees (WGS84 frame) and the altitude
* in meters AMSL (above mean sea level).
*
* The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise).
*/
rpc GotoLocation(GotoLocationRequest) returns(GotoLocationResponse) {}
/*
* Send command do orbit to the drone.
*
* This will run the orbit routine with the given parameters.
*/
rpc DoOrbit(DoOrbitRequest) returns(DoOrbitResponse) {}
/*
* Send command to hold position (a.k.a. "Loiter").
*
* Sends a command to drone to change to Hold flight mode, causing the
* vehicle to stop and maintain its current GPS position and altitude.
*
* Note: this command is specific to the PX4 Autopilot flight stack as
* it implies a change to a PX4-specific mode.
*/
rpc Hold(HoldRequest) returns(HoldResponse) {}
/*
* Send command to set the value of an actuator.
*
* Note that the index of the actuator starts at 1 and that the value goes from -1 to 1.
*/
rpc SetActuator(SetActuatorRequest) returns(SetActuatorResponse) {}
/*
* 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). The command will succeed if called when the vehicle
* is already in fixedwing mode.
*/
rpc TransitionToFixedwing(TransitionToFixedwingRequest) returns(TransitionToFixedwingResponse) {}
/*
* 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). The command will succeed if called when the vehicle
* is already in multicopter mode.
*/
rpc TransitionToMulticopter(TransitionToMulticopterRequest) returns(TransitionToMulticopterResponse) {}
/*
* Get the takeoff altitude (in meters above ground).
*/
rpc GetTakeoffAltitude(GetTakeoffAltitudeRequest) returns(GetTakeoffAltitudeResponse) {}
/*
* Set takeoff altitude (in meters above ground).
*/
rpc SetTakeoffAltitude(SetTakeoffAltitudeRequest) returns(SetTakeoffAltitudeResponse) {}
/*
* Get the return to launch minimum return altitude (in meters).
*/
rpc GetReturnToLaunchAltitude(GetReturnToLaunchAltitudeRequest) returns(GetReturnToLaunchAltitudeResponse) {}
/*
* Set the return to launch minimum return altitude (in meters).
*/
rpc SetReturnToLaunchAltitude(SetReturnToLaunchAltitudeRequest) returns(SetReturnToLaunchAltitudeResponse) {}
/*
* Set current speed.
*
* This will set the speed during a mission, reposition, and similar.
* It is ephemeral, so not stored on the drone and does not survive a reboot.
*/
rpc SetCurrentSpeed(SetCurrentSpeedRequest) returns(SetCurrentSpeedResponse) {}
}
message ArmRequest {}
message ArmResponse {
ActionResult action_result = 1;
}
message ArmForceRequest {}
message ArmForceResponse {
ActionResult action_result = 1;
}
message DisarmRequest {}
message DisarmResponse {
ActionResult action_result = 1;
}
message TakeoffRequest {}
message TakeoffResponse {
ActionResult action_result = 1;
}
message LandRequest {}
message LandResponse {
ActionResult action_result = 1;
}
message RebootRequest {}
message RebootResponse {
ActionResult action_result = 1;
}
message ShutdownRequest {}
message ShutdownResponse {
ActionResult action_result = 1;
}
message TerminateRequest {}
message TerminateResponse {
ActionResult action_result = 1;
}
message KillRequest {}
message KillResponse {
ActionResult action_result = 1;
}
message ReturnToLaunchRequest {}
message ReturnToLaunchResponse {
ActionResult action_result = 1;
}
message GotoLocationRequest {
double latitude_deg = 1; // Latitude (in degrees)
double longitude_deg = 2; // Longitude (in degrees)
float absolute_altitude_m = 3; // Altitude AMSL (in meters)
float yaw_deg = 4; // Yaw angle (in degrees, frame is NED, 0 is North, positive is clockwise)
}
message GotoLocationResponse {
ActionResult action_result = 1;
}
// Yaw behaviour during orbit flight.
enum OrbitYawBehavior {
ORBIT_YAW_BEHAVIOR_HOLD_FRONT_TO_CIRCLE_CENTER = 0; // Vehicle front points to the center (default)
ORBIT_YAW_BEHAVIOR_HOLD_INITIAL_HEADING = 1; // Vehicle front holds heading when message received
ORBIT_YAW_BEHAVIOR_UNCONTROLLED = 2; // Yaw uncontrolled
ORBIT_YAW_BEHAVIOR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3; // Vehicle front follows flight path (tangential to circle)
ORBIT_YAW_BEHAVIOR_RC_CONTROLLED = 4; // Yaw controlled by RC input
}
message DoOrbitRequest {
float radius_m = 1; // Radius of circle (in meters)
float velocity_ms = 2; // Tangential velocity (in m/s)
OrbitYawBehavior yaw_behavior = 3; // Yaw behavior of vehicle (ORBIT_YAW_BEHAVIOUR)
double latitude_deg = 5 [(mavsdk.options.default_value)="NaN"]; // Center point latitude in degrees. NAN: use current latitude for center
double longitude_deg = 6 [(mavsdk.options.default_value)="NaN"]; // Center point longitude in degrees. NAN: use current longitude for center
double absolute_altitude_m = 7 [(mavsdk.options.default_value)="NaN"]; // Center point altitude in meters. NAN: use current altitude for center
}
message DoOrbitResponse {
ActionResult action_result = 1;
}
message HoldRequest {}
message HoldResponse {
ActionResult action_result = 1;
}
message SetActuatorRequest {
int32 index = 1; // Index of actuator (starting with 1)
float value = 2; // Value to set the actuator to (normalized from [-1..1])
}
message SetActuatorResponse {
ActionResult action_result = 1;
}
message TransitionToFixedwingRequest {}
message TransitionToFixedwingResponse {
ActionResult action_result = 1;
}
message TransitionToMulticopterRequest {}
message TransitionToMulticopterResponse {
ActionResult action_result = 1;
}
message GetTakeoffAltitudeRequest {}
message GetTakeoffAltitudeResponse {
ActionResult action_result = 1;
float altitude = 2; // Takeoff altitude relative to ground/takeoff location (in meters)
}
message SetTakeoffAltitudeRequest {
float altitude = 1; // Takeoff altitude relative to ground/takeoff location (in meters)
}
message SetTakeoffAltitudeResponse {
ActionResult action_result = 1;
}
message GetReturnToLaunchAltitudeRequest {}
message GetReturnToLaunchAltitudeResponse {
ActionResult action_result = 1;
float relative_altitude_m = 2; // Return altitude relative to takeoff location (in meters)
}
message SetReturnToLaunchAltitudeRequest {
float relative_altitude_m = 1; // Return altitude relative to takeoff location (in meters)
}
message SetReturnToLaunchAltitudeResponse {
ActionResult action_result = 1;
}
message SetCurrentSpeedRequest {
float speed_m_s = 1; // Speed in meters/second
}
message SetCurrentSpeedResponse {
ActionResult action_result = 1;
}
// Result type.
message ActionResult {
// Possible results returned for action requests.
enum Result {
RESULT_UNKNOWN = 0; // Unknown result
RESULT_SUCCESS = 1; // Request was successful
RESULT_NO_SYSTEM = 2; // No system is connected
RESULT_CONNECTION_ERROR = 3; // Connection error
RESULT_BUSY = 4; // Vehicle is busy
RESULT_COMMAND_DENIED = 5; // Command refused by vehicle
RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN = 6; // Command refused because landed state is unknown
RESULT_COMMAND_DENIED_NOT_LANDED = 7; // Command refused because vehicle not landed
RESULT_TIMEOUT = 8; // Request timed out
RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN = 9; // Hybrid/VTOL transition support is unknown
RESULT_NO_VTOL_TRANSITION_SUPPORT = 10; // Vehicle does not support hybrid/VTOL transitions
RESULT_PARAMETER_ERROR = 11; // Error getting or setting parameter
RESULT_UNSUPPORTED = 12; // Action not supported
RESULT_FAILED = 13; // Action failed
RESULT_INVALID_ARGUMENT = 14; // Invalid argument
}
Result result = 1; // Result enum value
string result_str = 2; // Human-readable English string describing the result
}