-
Notifications
You must be signed in to change notification settings - Fork 88
/
camera.proto
545 lines (483 loc) · 17.7 KB
/
camera.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
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
syntax = "proto3";
package mavsdk.rpc.camera;
import "mavsdk_options.proto";
option java_package = "io.mavsdk.camera";
option java_outer_classname = "CameraProto";
/*
* Can be used to manage cameras that implement the MAVLink
* Camera Protocol: https://mavlink.io/en/protocol/camera.html.
*
* Currently only a single camera is supported.
* When multiple cameras are supported the plugin will need to be
* instantiated separately for every camera and the camera selected using
* `select_camera`.
*/
service CameraService {
/*
* Prepare the camera plugin (e.g. download the camera definition, etc).
*/
rpc Prepare(PrepareRequest) returns(PrepareResponse) {}
/*
* Take one photo.
*/
rpc TakePhoto(TakePhotoRequest) returns(TakePhotoResponse) {}
/*
* Start photo timelapse with a given interval.
*/
rpc StartPhotoInterval(StartPhotoIntervalRequest) returns(StartPhotoIntervalResponse) {}
/*
* Stop a running photo timelapse.
*/
rpc StopPhotoInterval(StopPhotoIntervalRequest) returns(StopPhotoIntervalResponse) {}
/*
* Start a video recording.
*/
rpc StartVideo(StartVideoRequest) returns(StartVideoResponse) {}
/*
* Stop a running video recording.
*/
rpc StopVideo(StopVideoRequest) returns(StopVideoResponse) {}
/*
* Start video streaming.
*/
rpc StartVideoStreaming(StartVideoStreamingRequest) returns(StartVideoStreamingResponse) { option (mavsdk.options.async_type) = SYNC; }
/*
* Stop current video streaming.
*/
rpc StopVideoStreaming(StopVideoStreamingRequest) returns(StopVideoStreamingResponse) { option (mavsdk.options.async_type) = SYNC; }
/*
* Set camera mode.
*/
rpc SetMode(SetModeRequest) returns(SetModeResponse) {}
/*
* List photos available on the camera.
*/
rpc ListPhotos(ListPhotosRequest) returns(ListPhotosResponse) {}
/*
* Subscribe to camera mode updates.
*/
rpc SubscribeMode(SubscribeModeRequest) returns(stream ModeResponse) {}
/*
* Subscribe to camera information updates.
*/
rpc SubscribeInformation(SubscribeInformationRequest) returns(stream InformationResponse) {}
/*
* Subscribe to video stream info updates.
*/
rpc SubscribeVideoStreamInfo(SubscribeVideoStreamInfoRequest) returns(stream VideoStreamInfoResponse) {}
/*
* Subscribe to capture info updates.
*/
rpc SubscribeCaptureInfo(SubscribeCaptureInfoRequest) returns(stream CaptureInfoResponse) { option (mavsdk.options.async_type) = ASYNC; }
/*
* Subscribe to camera status updates.
*/
rpc SubscribeStatus(SubscribeStatusRequest) returns(stream StatusResponse) {}
/*
* Get the list of current camera settings.
*/
rpc SubscribeCurrentSettings(SubscribeCurrentSettingsRequest) returns(stream CurrentSettingsResponse) { option (mavsdk.options.async_type) = ASYNC; }
/*
* Get the list of settings that can be changed.
*/
rpc SubscribePossibleSettingOptions(SubscribePossibleSettingOptionsRequest) returns(stream PossibleSettingOptionsResponse) {}
/*
* Set a setting to some value.
*
* Only setting_id of setting and option_id of option needs to be set.
*/
rpc SetSetting(SetSettingRequest) returns(SetSettingResponse) {}
/*
* Get a setting.
*
* Only setting_id of setting needs to be set.
*/
rpc GetSetting(GetSettingRequest) returns(GetSettingResponse) {}
/*
* Format storage (e.g. SD card) in camera.
*
* This will delete all content of the camera storage!
*/
rpc FormatStorage(FormatStorageRequest) returns(FormatStorageResponse) {}
/*
* Select current camera .
*
* Bind the plugin instance to a specific camera_id
*/
rpc SelectCamera(SelectCameraRequest) returns(SelectCameraResponse) { option (mavsdk.options.async_type) = SYNC; }
/*
* Reset all settings in camera.
*
* This will reset all camera settings to default value
*/
rpc ResetSettings(ResetSettingsRequest) returns(ResetSettingsResponse) {}
/*
* Start zooming in.
*/
rpc ZoomInStart(ZoomInStartRequest) returns(ZoomInStartResponse) {}
/*
* Start zooming out.
*/
rpc ZoomOutStart(ZoomOutStartRequest) returns(ZoomOutStartResponse) {}
/*
* Stop zooming.
*/
rpc ZoomStop(ZoomStopRequest) returns(ZoomStopResponse) {}
/*
* Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0).
*/
rpc ZoomRange(ZoomRangeRequest) returns(ZoomRangeResponse) {}
/*
* Track point.
*/
rpc TrackPoint(TrackPointRequest) returns(TrackPointResponse) {}
/*
* Track rectangle.
*/
rpc TrackRectangle(TrackRectangleRequest) returns(TrackRectangleResponse) {}
/*
* Stop tracking.
*/
rpc TrackStop(TrackStopRequest) returns(TrackStopResponse) {}
/*
* Start focusing in.
*/
rpc FocusInStart(FocusInStartRequest) returns(FocusInStartResponse) {}
/*
* Start focusing out.
*/
rpc FocusOutStart(FocusOutStartRequest) returns(FocusOutStartResponse) {}
/*
* Stop focus.
*/
rpc FocusStop(FocusStopRequest) returns(FocusStopResponse) {}
/*
* Focus with range value of full range (value between 0.0 and 100.0).
*/
rpc FocusRange(FocusRangeRequest) returns(FocusRangeResponse) {}
}
message PrepareRequest {}
message PrepareResponse {
CameraResult camera_result = 1;
}
message TakePhotoRequest {}
message TakePhotoResponse {
CameraResult camera_result = 1;
}
message StartPhotoIntervalRequest {
float interval_s = 1; // Interval between photos (in seconds)
}
message StartPhotoIntervalResponse {
CameraResult camera_result = 1;
}
message StopPhotoIntervalRequest {}
message StopPhotoIntervalResponse {
CameraResult camera_result = 1;
}
message StartVideoRequest {}
message StartVideoResponse {
CameraResult camera_result = 1;
}
message StopVideoRequest {}
message StopVideoResponse {
CameraResult camera_result = 1;
}
message StartVideoStreamingRequest {
int32 stream_id = 1; // video stream id
}
message StartVideoStreamingResponse {
CameraResult camera_result = 1;
}
message StopVideoStreamingRequest {
int32 stream_id = 1; // video stream id
}
message StopVideoStreamingResponse {
CameraResult camera_result = 1;
}
message SetModeRequest {
Mode mode = 1; // Camera mode to set
}
message SetModeResponse {
CameraResult camera_result = 1;
}
message ListPhotosRequest {
PhotosRange photos_range = 1; // Which photos should be listed (all or since connection)
}
message ListPhotosResponse {
CameraResult camera_result = 1;
repeated CaptureInfo capture_infos = 2; // List of capture infos (representing the photos)
}
message SubscribeInformationRequest {}
message InformationResponse {
Information information = 1; // Camera information
}
message SubscribeModeRequest {}
message ModeResponse {
Mode mode = 1; // Camera mode
}
message SubscribeVideoStreamInfoRequest {}
message VideoStreamInfoResponse {
VideoStreamInfo video_stream_info = 1; // Video stream info
}
message SubscribeCaptureInfoRequest {}
message CaptureInfoResponse {
CaptureInfo capture_info = 1; // Capture info
}
message SubscribeStatusRequest {}
message StatusResponse {
Status camera_status = 1; // Camera status
}
message SubscribeCurrentSettingsRequest {}
message CurrentSettingsResponse {
repeated Setting current_settings = 1; // List of current settings
}
message SubscribePossibleSettingOptionsRequest {}
message PossibleSettingOptionsResponse {
repeated SettingOptions setting_options = 1; // List of settings that can be changed
}
message SetSettingRequest {
Setting setting = 1; // Desired setting
}
message SetSettingResponse {
CameraResult camera_result = 1;
}
message GetSettingRequest {
Setting setting = 1; // Requested setting
}
message GetSettingResponse {
CameraResult camera_result = 1;
Setting setting = 2; // Setting
}
message FormatStorageRequest {
int32 storage_id = 1; //Storage identify to be format
}
message FormatStorageResponse {
CameraResult camera_result = 1;
}
message SelectCameraResponse {
CameraResult camera_result = 1;
}
message SelectCameraRequest {
int32 camera_id = 1; // Id of camera to be selected
}
message ResetSettingsRequest {}
message ResetSettingsResponse {
CameraResult camera_result = 1;
}
message ZoomInStartRequest {}
message ZoomInStartResponse {
CameraResult camera_result = 1;
}
message ZoomOutStartRequest {}
message ZoomOutStartResponse {
CameraResult camera_result = 1;
}
message ZoomStopRequest {}
message ZoomStopResponse {
CameraResult camera_result = 1;
}
message ZoomRangeRequest {
float range = 1; // Range must be between 0.0 and 100.0
}
message ZoomRangeResponse {
CameraResult camera_result = 1;
}
message TrackPointRequest {
float point_x = 1; // Point in X axis (0..1, 0 is left, 1 is right)
float point_y = 2; // Point in Y axis (0..1, 0 is top, 1 is bottom)
float radius = 3; // Radius (0 is one pixel, 1 is full image width)
}
message TrackPointResponse {
CameraResult camera_result = 1;
}
message TrackRectangleRequest {
float top_left_x = 1; // Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right)
float top_left_y = 2; // Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom)
float bottom_right_x = 3; // Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right)
float bottom_right_y = 4; // Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom)
}
message TrackRectangleResponse {
CameraResult camera_result = 1;
}
message TrackStopRequest {}
message TrackStopResponse {
CameraResult camera_result = 1;
}
message FocusInStartRequest {}
message FocusInStartResponse {
CameraResult camera_result = 1;
}
message FocusOutStartRequest {}
message FocusOutStartResponse {
CameraResult camera_result = 1;
}
message FocusStopRequest {}
message FocusStopResponse {
CameraResult camera_result = 1;
}
message FocusRangeRequest {
float range = 1; // Range must be between 0.0 - 100.0
}
message FocusRangeResponse {
CameraResult camera_result = 1;
}
// Result type.
message CameraResult {
// Possible results returned for camera commands
enum Result {
RESULT_UNKNOWN = 0; // Unknown result
RESULT_SUCCESS = 1; // Command executed successfully
RESULT_IN_PROGRESS = 2; // Command in progress
RESULT_BUSY = 3; // Camera is busy and rejected command
RESULT_DENIED = 4; // Camera denied the command
RESULT_ERROR = 5; // An error has occurred while executing the command
RESULT_TIMEOUT = 6; // Command timed out
RESULT_WRONG_ARGUMENT = 7; // Command has wrong argument(s)
RESULT_NO_SYSTEM = 8; // No system connected
RESULT_PROTOCOL_UNSUPPORTED = 9; // Definition file protocol not supported
}
Result result = 1; // Result enum value
string result_str = 2; // Human-readable English string describing the result
}
// Camera mode type.
enum Mode {
MODE_UNKNOWN = 0; // Unknown
MODE_PHOTO = 1; // Photo mode
MODE_VIDEO = 2; // Video mode
}
// Photos range type.
enum PhotosRange {
PHOTOS_RANGE_ALL = 0; // All the photos present on the camera
PHOTOS_RANGE_SINCE_CONNECTION = 1; // Photos taken since MAVSDK got connected
}
// Position type in global coordinates.
message Position {
double latitude_deg = 1; // Latitude in degrees (range: -90 to +90)
double longitude_deg = 2; // Longitude in degrees (range: -180 to +180)
float absolute_altitude_m = 3; // Altitude AMSL (above mean sea level) in metres
float relative_altitude_m = 4; // Altitude relative to takeoff altitude in metres
}
/*
* Quaternion type.
*
* All rotations and axis systems follow the right-hand rule.
* The Hamilton quaternion product definition is used.
* A zero-rotation quaternion is represented by (1,0,0,0).
* The quaternion could also be written as w + xi + yj + zk.
*
* For more info see: https://en.wikipedia.org/wiki/Quaternion
*/
message Quaternion {
float w = 1; // Quaternion entry 0, also denoted as a
float x = 2; // Quaternion entry 1, also denoted as b
float y = 3; // Quaternion entry 2, also denoted as c
float z = 4; // Quaternion entry 3, also denoted as d
}
/*
* Euler angle type.
*
* All rotations and axis systems follow the right-hand rule.
* The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence.
*
* For more info see https://en.wikipedia.org/wiki/Euler_angles
*/
message EulerAngle {
float roll_deg = 1; // Roll angle in degrees, positive is banking to the right
float pitch_deg = 2; // Pitch angle in degrees, positive is pitching nose up
float yaw_deg = 3; // Yaw angle in degrees, positive is clock-wise seen from above
}
// Information about a picture just captured.
message CaptureInfo {
Position position = 1; // Location where the picture was taken
Quaternion attitude_quaternion = 2; // Attitude of the camera when the picture was taken (quaternion)
EulerAngle attitude_euler_angle = 3; // Attitude of the camera when the picture was taken (euler angle)
uint64 time_utc_us = 4; // Timestamp in UTC (since UNIX epoch) in microseconds
bool is_success = 5; // True if the capture was successful
int32 index = 6; // Zero-based index of this image since vehicle was armed
string file_url = 7; // Download URL of this image
}
// Type for video stream settings.
message VideoStreamSettings {
float frame_rate_hz = 1; // Frames per second
uint32 horizontal_resolution_pix = 2; // Horizontal resolution (in pixels)
uint32 vertical_resolution_pix = 3; // Vertical resolution (in pixels)
uint32 bit_rate_b_s = 4; // Bit rate (in bits per second)
uint32 rotation_deg = 5; // Video image rotation (clockwise, 0-359 degrees)
string uri = 6; // Video stream URI
float horizontal_fov_deg = 7; // Horizontal fov in degrees
}
// Information about the video stream.
message VideoStreamInfo {
// Video stream status type.
enum VideoStreamStatus {
VIDEO_STREAM_STATUS_NOT_RUNNING = 0; // Video stream is not running
VIDEO_STREAM_STATUS_IN_PROGRESS = 1; // Video stream is running
}
// Video stream light spectrum type
enum VideoStreamSpectrum {
VIDEO_STREAM_SPECTRUM_UNKNOWN = 0; // Unknown
VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT = 1; // Visible light
VIDEO_STREAM_SPECTRUM_INFRARED = 2; // Infrared
}
VideoStreamSettings settings = 1; // Video stream settings
VideoStreamStatus status = 2; // Current status of video streaming
VideoStreamSpectrum spectrum = 3; // Light-spectrum of the video stream
}
// Information about the camera status.
message Status {
// Storage status type.
enum StorageStatus {
STORAGE_STATUS_NOT_AVAILABLE = 0; // Status not available
STORAGE_STATUS_UNFORMATTED = 1; // Storage is not formatted (i.e. has no recognized file system)
STORAGE_STATUS_FORMATTED = 2; // Storage is formatted (i.e. has recognized a file system)
STORAGE_STATUS_NOT_SUPPORTED = 3; // Storage status is not supported
}
// Storage type.
enum StorageType {
STORAGE_TYPE_UNKNOWN = 0; // Storage type unknown
STORAGE_TYPE_USB_STICK = 1; // Storage type USB stick
STORAGE_TYPE_SD = 2; // Storage type SD card
STORAGE_TYPE_MICROSD = 3; // Storage type MicroSD card
STORAGE_TYPE_HD = 7; // Storage type HD mass storage
STORAGE_TYPE_OTHER = 254; // Storage type other, not listed
}
bool video_on = 1; // Whether video recording is currently in process
bool photo_interval_on = 2; // Whether a photo interval is currently in process
float used_storage_mib = 3; // Used storage (in MiB)
float available_storage_mib = 4; // Available storage (in MiB)
float total_storage_mib = 5; // Total storage (in MiB)
float recording_time_s = 6; // Elapsed time since starting the video recording (in seconds)
string media_folder_name = 7; // Current folder name where media are saved
StorageStatus storage_status = 8; // Storage status
uint32 storage_id = 9; // Storage ID starting at 1
StorageType storage_type = 10; // Storage type
}
// Type to represent a setting option.
message Option {
string option_id = 1; // Name of the option (machine readable)
string option_description = 2; // Description of the option (human readable)
}
// Type to represent a setting with a selected option.
message Setting {
string setting_id = 1; // Name of a setting (machine readable)
string setting_description = 2; // Description of the setting (human readable). This field is meant to be read from the drone, ignore it when setting.
Option option = 3; // Selected option
bool is_range = 4; // If option is given as a range. This field is meant to be read from the drone, ignore it when setting.
}
// Type to represent a setting with a list of options to choose from.
message SettingOptions {
string setting_id = 1; // Name of the setting (machine readable)
string setting_description = 2; // Description of the setting (human readable)
repeated Option options = 3; // List of options or if range [min, max] or [min, max, interval]
bool is_range = 4; // If option is given as a range
}
// Type to represent a camera information.
message Information {
string vendor_name = 1; // Name of the camera vendor
string model_name = 2; // Name of the camera model
float focal_length_mm = 3; // Focal length
float horizontal_sensor_size_mm = 4; // Horizontal sensor size
float vertical_sensor_size_mm = 5; // Vertical sensor size
uint32 horizontal_resolution_px = 6; // Horizontal image resolution in pixels
uint32 vertical_resolution_px = 7; // Vertical image resolution in pixels
}