Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add more camera function #318

Merged
merged 1 commit into from
Jun 17, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 16 additions & 1 deletion protos/camera_server/camera_server.proto
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,12 @@ service CameraServerService {

// Respond to an image capture request from SubscribeTakePhoto.
rpc RespondTakePhoto(RespondTakePhotoRequest) returns(RespondTakePhotoResponse) { option (mavsdk.options.async_type) = SYNC; }

// Subscribe to start video requests. Each request received should response to using StartVideoResponse
rpc SubscribeStartVideo(SubscribeStartVideoRequest) returns(stream StartVideoResponse) { option (mavsdk.options.async_type) = ASYNC; }

// Subscribe to stop video requests. Each request received should response to using StopVideoResponse
rpc SubscribeStopVideo(SubscribeStopVideoRequest) returns(stream StopVideoResponse) { option (mavsdk.options.async_type) = ASYNC; }
}

message SetInformationRequest {
Expand All @@ -38,11 +44,20 @@ message SetInProgressResponse {
}

message SubscribeTakePhotoRequest {}

message TakePhotoResponse {
int32 index = 1;
}

message SubscribeStartVideoRequest {}
message StartVideoResponse {
int32 stream_id = 1; // video stream id
}

message SubscribeStopVideoRequest {}
message StopVideoResponse {
int32 stream_id = 1; // video stream id
}

// Possible results when taking a photo.
enum TakePhotoFeedback {
TAKE_PHOTO_FEEDBACK_UNKNOWN = 0; // Unknown
Expand Down