From 0e836426e4565007bb743cb6beec6e9f4a655d7e Mon Sep 17 00:00:00 2001 From: denys Date: Wed, 31 Jan 2024 11:13:06 +0100 Subject: [PATCH 1/3] Capability flags in camera information --- protos/camera_server/camera_server.proto | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/protos/camera_server/camera_server.proto b/protos/camera_server/camera_server.proto index 99d2b69d..bff4b69d 100644 --- a/protos/camera_server/camera_server.proto +++ b/protos/camera_server/camera_server.proto @@ -317,8 +317,9 @@ message Information { uint32 horizontal_resolution_px = 7; // Horizontal image resolution in pixels uint32 vertical_resolution_px = 8; // Vertical image resolution in pixels uint32 lens_id = 9; // Lens ID - uint32 definition_file_version = 10; // Camera definition file version (iteration) - string definition_file_uri = 11; // Camera definition URI (http or mavlink ftp) + uint32 flags = 10; // Bitmap of camera capability flags + uint32 definition_file_version = 11; // Camera definition file version (iteration) + string definition_file_uri = 12; // Camera definition URI (http or mavlink ftp) } // Type to represent video streaming settings From bd8078ca1d9ad20a5b779e5558bc1b7292ab8577 Mon Sep 17 00:00:00 2001 From: denys Date: Sun, 4 Feb 2024 11:51:07 +0100 Subject: [PATCH 2/3] Modified camera cap flags setting format from uint32 to a separate message --- protos/camera_server/camera_server.proto | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/protos/camera_server/camera_server.proto b/protos/camera_server/camera_server.proto index bff4b69d..0a70b383 100644 --- a/protos/camera_server/camera_server.proto +++ b/protos/camera_server/camera_server.proto @@ -306,6 +306,28 @@ enum CameraFeedback { CAMERA_FEEDBACK_FAILED = 3; // Failed } +/* + * Camera capability flags as defined in MavLink: + * https://mavlink.io/en/messages/common.html#CAMERA_CAP_FLAGS + * + * Multiple status fields can be set simultaneously. Mavlink does + * not specify which states are mutually exclusive. + */ +message CameraCapFlags { + bool capture_video = 1; // Camera is able to record video + bool capture_image = 2; // Camera is able to capture images + bool has_modes = 3; // Camera has separate Video and Image/Photo modes + bool can_capture_image_in_video_mode = 4; // Camera can capture images while in video mode + bool can_capture_video_in_image_mode = 5; // Camera can capture videos while in Photo/Image mode + bool has_image_survey_mode = 6; // Camera has image survey mode + bool has_basic_zoom = 7; // Camera has basic zoom control + bool has_basic_focus = 8; // Camera has basic focus control + bool has_video_stream = 9; // Camera has video streaming capabilities + bool has_tracking_point = 10; // Camera supports tracking of a point on the camera view + bool has_tracking_rectangle = 11; // Camera supports tracking of a selection rectangle on the camera view + bool has_tracking_geo_status = 12; // Camera supports tracking geo status +} + // Type to represent a camera information. message Information { string vendor_name = 1; // Name of the camera vendor @@ -317,7 +339,7 @@ message Information { uint32 horizontal_resolution_px = 7; // Horizontal image resolution in pixels uint32 vertical_resolution_px = 8; // Vertical image resolution in pixels uint32 lens_id = 9; // Lens ID - uint32 flags = 10; // Bitmap of camera capability flags + CameraCapFlags flags = 10; // Camera capability flags uint32 definition_file_version = 11; // Camera definition file version (iteration) string definition_file_uri = 12; // Camera definition URI (http or mavlink ftp) } From 5431eb9c4524da4696f383d3bbdb35a70db68bbf Mon Sep 17 00:00:00 2001 From: denys Date: Mon, 19 Feb 2024 02:14:38 +0100 Subject: [PATCH 3/3] Merged tracking_server plugin into camera_server --- protos/camera_server/camera_server.proto | 118 +++++++++++++++---- protos/tracking_server/tracking_server.proto | 117 ------------------ 2 files changed, 92 insertions(+), 143 deletions(-) delete mode 100644 protos/tracking_server/tracking_server.proto diff --git a/protos/camera_server/camera_server.proto b/protos/camera_server/camera_server.proto index 0a70b383..f39fe43c 100644 --- a/protos/camera_server/camera_server.proto +++ b/protos/camera_server/camera_server.proto @@ -7,7 +7,7 @@ import "mavsdk_options.proto"; option java_package = "io.mavsdk.camera_server"; option java_outer_classname = "CameraServerProto"; -// Provides handling of camera trigger commands. +// Provides handling of camera interface service CameraServerService { // Sets the camera information. This must be called as soon as the camera server is created. rpc SetInformation(SetInformationRequest) returns(SetInformationResponse) { option (mavsdk.options.async_type) = SYNC; } @@ -101,8 +101,33 @@ service CameraServerService { // Respond to zoom range. rpc RespondZoomRange(RespondZoomRangeRequest) returns(RespondZoomRangeResponse) { option (mavsdk.options.async_type) = SYNC; } + + // Set/update the current rectangle tracking status. + rpc SetTrackingRectangleStatus(SetTrackingRectangleStatusRequest) returns(SetTrackingRectangleStatusResponse) { option (mavsdk.options.async_type) = SYNC; } + + // Set the current tracking status to off. + rpc SetTrackingOffStatus(SetTrackingOffStatusRequest) returns(SetTrackingOffStatusResponse) { option (mavsdk.options.async_type) = SYNC; } + + // Subscribe to incoming tracking point command. + rpc SubscribeTrackingPointCommand(SubscribeTrackingPointCommandRequest) returns(stream TrackingPointCommandResponse) { option (mavsdk.options.async_type) = ASYNC; } + + // Subscribe to incoming tracking rectangle command. + rpc SubscribeTrackingRectangleCommand(SubscribeTrackingRectangleCommandRequest) returns(stream TrackingRectangleCommandResponse) { option (mavsdk.options.async_type) = ASYNC; } + + // Subscribe to incoming tracking off command. + rpc SubscribeTrackingOffCommand(SubscribeTrackingOffCommandRequest) returns(stream TrackingOffCommandResponse) { option (mavsdk.options.async_type) = ASYNC; } + + // Respond to an incoming tracking point command. + rpc RespondTrackingPointCommand(RespondTrackingPointCommandRequest) returns(RespondTrackingPointCommandResponse) { option (mavsdk.options.async_type) = SYNC; } + + // Respond to an incoming tracking rectangle command. + rpc RespondTrackingRectangleCommand(RespondTrackingRectangleCommandRequest) returns(RespondTrackingRectangleCommandResponse) { option (mavsdk.options.async_type) = SYNC; } + + // Respond to an incoming tracking off command. + rpc RespondTrackingOffCommand(RespondTrackingOffCommandRequest) returns(RespondTrackingOffCommandResponse) { option (mavsdk.options.async_type) = SYNC; } } + message SetInformationRequest { Information information = 1; // information about the camera } @@ -306,28 +331,6 @@ enum CameraFeedback { CAMERA_FEEDBACK_FAILED = 3; // Failed } -/* - * Camera capability flags as defined in MavLink: - * https://mavlink.io/en/messages/common.html#CAMERA_CAP_FLAGS - * - * Multiple status fields can be set simultaneously. Mavlink does - * not specify which states are mutually exclusive. - */ -message CameraCapFlags { - bool capture_video = 1; // Camera is able to record video - bool capture_image = 2; // Camera is able to capture images - bool has_modes = 3; // Camera has separate Video and Image/Photo modes - bool can_capture_image_in_video_mode = 4; // Camera can capture images while in video mode - bool can_capture_video_in_image_mode = 5; // Camera can capture videos while in Photo/Image mode - bool has_image_survey_mode = 6; // Camera has image survey mode - bool has_basic_zoom = 7; // Camera has basic zoom control - bool has_basic_focus = 8; // Camera has basic focus control - bool has_video_stream = 9; // Camera has video streaming capabilities - bool has_tracking_point = 10; // Camera supports tracking of a point on the camera view - bool has_tracking_rectangle = 11; // Camera supports tracking of a selection rectangle on the camera view - bool has_tracking_geo_status = 12; // Camera supports tracking geo status -} - // Type to represent a camera information. message Information { string vendor_name = 1; // Name of the camera vendor @@ -339,9 +342,8 @@ message Information { uint32 horizontal_resolution_px = 7; // Horizontal image resolution in pixels uint32 vertical_resolution_px = 8; // Vertical image resolution in pixels uint32 lens_id = 9; // Lens ID - CameraCapFlags flags = 10; // Camera capability flags - uint32 definition_file_version = 11; // Camera definition file version (iteration) - string definition_file_uri = 12; // Camera definition URI (http or mavlink ftp) + uint32 definition_file_version = 10; // Camera definition file version (iteration) + string definition_file_uri = 11; // Camera definition URI (http or mavlink ftp) } // Type to represent video streaming settings @@ -463,3 +465,67 @@ message CaptureStatus { VideoStatus video_status = 5; // Current status of video capturing int32 image_count = 6; // Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT) } + +message SetTrackingPointStatusRequest { + TrackPoint tracked_point = 1; // The tracked point +} +message SetTrackingPointStatusResponse {} + +message SetTrackingRectangleStatusRequest { + TrackRectangle tracked_rectangle = 1; // The tracked rectangle +} +message SetTrackingRectangleStatusResponse {} + +message SetTrackingOffStatusRequest {} +message SetTrackingOffStatusResponse {} + +message SubscribeTrackingPointCommandRequest {} +message TrackingPointCommandResponse { + TrackPoint track_point = 1; // The point to track if a point is to be tracked +} + +message SubscribeTrackingRectangleCommandRequest {} +message TrackingRectangleCommandResponse { + TrackRectangle track_rectangle = 1; // The point to track if a point is to be tracked +} + +message SubscribeTrackingOffCommandRequest {} +message TrackingOffCommandResponse { + int32 dummy = 1; // Unused +} + +message RespondTrackingPointCommandRequest { + CameraFeedback stop_video_feedback = 1; // the feedback +} +message RespondTrackingPointCommandResponse { + CameraServerResult camera_server_result = 1; // The result of sending the response. +} + +message RespondTrackingRectangleCommandRequest { + CameraFeedback stop_video_feedback = 1; // the feedback +} +message RespondTrackingRectangleCommandResponse { + CameraServerResult camera_server_result = 1; // The result of sending the response. +} + +message RespondTrackingOffCommandRequest { + CameraFeedback stop_video_feedback = 1; // the feedback +} +message RespondTrackingOffCommandResponse { + CameraServerResult camera_server_result = 1; // The result of sending the response. +} + +// Point description type +message TrackPoint { + float point_x = 1; // Point to track x value (normalized 0..1, 0 is left, 1 is right). + float point_y = 2; // Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + float radius = 3; // Point to track y value (normalized 0..1, 0 is top, 1 is bottom). +} + +// Rectangle description type +message TrackRectangle { + float top_left_corner_x = 1; // Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + float top_left_corner_y = 2; // Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + float bottom_right_corner_x = 3; // Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + float bottom_right_corner_y = 4; // Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). +} diff --git a/protos/tracking_server/tracking_server.proto b/protos/tracking_server/tracking_server.proto deleted file mode 100644 index 2eb671b3..00000000 --- a/protos/tracking_server/tracking_server.proto +++ /dev/null @@ -1,117 +0,0 @@ -syntax = "proto3"; - -package mavsdk.rpc.tracking_server; - -import "mavsdk_options.proto"; - -option java_package = "io.mavsdk.tracking_server"; -option java_outer_classname = "TrackingServerProto"; - -// API for an onboard image tracking software. -service TrackingServerService { - // Set/update the current point tracking status. - rpc SetTrackingPointStatus(SetTrackingPointStatusRequest) returns(SetTrackingPointStatusResponse) { option (mavsdk.options.async_type) = SYNC; } - // Set/update the current rectangle tracking status. - rpc SetTrackingRectangleStatus(SetTrackingRectangleStatusRequest) returns(SetTrackingRectangleStatusResponse) { option (mavsdk.options.async_type) = SYNC; } - // Set the current tracking status to off. - rpc SetTrackingOffStatus(SetTrackingOffStatusRequest) returns(SetTrackingOffStatusResponse) { option (mavsdk.options.async_type) = SYNC; } - // Subscribe to incoming tracking point command. - rpc SubscribeTrackingPointCommand(SubscribeTrackingPointCommandRequest) returns(stream TrackingPointCommandResponse) { option (mavsdk.options.async_type) = ASYNC; } - // Subscribe to incoming tracking rectangle command. - rpc SubscribeTrackingRectangleCommand(SubscribeTrackingRectangleCommandRequest) returns(stream TrackingRectangleCommandResponse) { option (mavsdk.options.async_type) = ASYNC; } - // Subscribe to incoming tracking off command. - rpc SubscribeTrackingOffCommand(SubscribeTrackingOffCommandRequest) returns(stream TrackingOffCommandResponse) { option (mavsdk.options.async_type) = ASYNC; } - // Respond to an incoming tracking point command. - rpc RespondTrackingPointCommand(RespondTrackingPointCommandRequest) returns(RespondTrackingPointCommandResponse) { option (mavsdk.options.async_type) = SYNC; } - // Respond to an incoming tracking rectangle command. - rpc RespondTrackingRectangleCommand(RespondTrackingRectangleCommandRequest) returns(RespondTrackingRectangleCommandResponse) { option (mavsdk.options.async_type) = SYNC; } - // Respond to an incoming tracking off command. - rpc RespondTrackingOffCommand(RespondTrackingOffCommandRequest) returns(RespondTrackingOffCommandResponse) { option (mavsdk.options.async_type) = SYNC; } -} - -message SetTrackingPointStatusRequest { - TrackPoint tracked_point = 1; // The tracked point -} -message SetTrackingPointStatusResponse {} - -message SetTrackingRectangleStatusRequest { - TrackRectangle tracked_rectangle = 1; // The tracked rectangle -} -message SetTrackingRectangleStatusResponse {} - -message SetTrackingOffStatusRequest {} -message SetTrackingOffStatusResponse {} - -message SubscribeTrackingPointCommandRequest {} -message TrackingPointCommandResponse { - TrackPoint track_point = 1; // The point to track if a point is to be tracked -} - -message SubscribeTrackingRectangleCommandRequest {} -message TrackingRectangleCommandResponse { - TrackRectangle track_rectangle = 1; // The point to track if a point is to be tracked -} - -message SubscribeTrackingOffCommandRequest {} -message TrackingOffCommandResponse { - int32 dummy = 1; // Unused -} - -message RespondTrackingPointCommandRequest { - CommandAnswer command_answer = 1; // The ack to answer to the incoming command -} -message RespondTrackingPointCommandResponse { - TrackingServerResult tracking_server_result = 1; // The result of sending the response. -} - -message RespondTrackingRectangleCommandRequest { - CommandAnswer command_answer = 1; // The ack to answer to the incoming command -} -message RespondTrackingRectangleCommandResponse { - TrackingServerResult tracking_server_result = 1; // The result of sending the response. -} - -message RespondTrackingOffCommandRequest { - CommandAnswer command_answer = 1; // The ack to answer to the incoming command -} -message RespondTrackingOffCommandResponse { - TrackingServerResult tracking_server_result = 1; // The result of sending the response. -} - -// Point description type -message TrackPoint { - float point_x = 1; // Point to track x value (normalized 0..1, 0 is left, 1 is right). - float point_y = 2; // Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - float radius = 3; // Point to track y value (normalized 0..1, 0 is top, 1 is bottom). -} - -// Rectangle description type -message TrackRectangle { - float top_left_corner_x = 1; // Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - float top_left_corner_y = 2; // Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - float bottom_right_corner_x = 3; // Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - float bottom_right_corner_y = 4; // Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). -} - -// Answer to respond to an incoming command -enum CommandAnswer { - COMMAND_ANSWER_ACCEPTED = 0; // Command accepted - COMMAND_ANSWER_TEMPORARILY_REJECTED = 1; // Command temporarily rejected - COMMAND_ANSWER_DENIED = 2; // Command denied - COMMAND_ANSWER_UNSUPPORTED = 3; // Command unsupported - COMMAND_ANSWER_FAILED = 4; // Command failed -} - -// Result type -message TrackingServerResult { - // Possible results returned for tracking_server requests. - enum Result { - RESULT_UNKNOWN = 0; // Unknown result - RESULT_SUCCESS = 1; // Request succeeded - RESULT_NO_SYSTEM = 2; // No system is connected - RESULT_CONNECTION_ERROR = 3; // Connection error - } - - Result result = 1; // Result enum value - string result_str = 2; // Human-readable English string describing the result -}