diff --git a/protos/camera/camera.proto b/protos/camera/camera.proto index 79ad9a2f..72e5023b 100644 --- a/protos/camera/camera.proto +++ b/protos/camera/camera.proto @@ -190,7 +190,7 @@ message ModeResponse { message SubscribeVideoStreamInfoRequest {} message VideoStreamInfoResponse { - VideoStreamInfo video_stream_info = 1; // Video stream info + repeated VideoStreamInfo video_stream_infos = 1; // Video stream infos } message SubscribeCaptureInfoRequest {} @@ -356,9 +356,10 @@ message VideoStreamInfo { 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 + int32 stream_id = 1; // stream unique id + VideoStreamSettings settings = 2; // Video stream settings + VideoStreamStatus status = 3; // Current status of video streaming + VideoStreamSpectrum spectrum = 4; // Light-spectrum of the video stream } // Information about the camera status. @@ -421,11 +422,50 @@ message SettingOptions { // 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 + enum CameraCapFlags { + CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 0; // Camera is able to record video + CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 1; // Camera is able to capture images + CAMERA_CAP_FLAGS_HAS_MODES = + 2; // Camera has separate Video and Image/Photo modes + // (MAV_CMD_SET_CAMERA_MODE) + CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = + 3; // Camera can capture images while in video mode + CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = + 4; // Camera can capture videos while in Photo/Image mode + CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = + 5; // Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE) + CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = + 6; // Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM) + CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = + 7; // Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS) + CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = + 8; // Camera has video streaming capabilities (request + // VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for + // video streaming info) + CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = + 9; // Camera supports tracking of a point on the camera view. + CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = + 10; // Camera supports tracking of a selection rectangle on the + // camera view. + CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = + 11; // Camera supports tracking geo status + // (CAMERA_TRACKING_GEO_STATUS). + }; + string vendor_name = 1; // Name of the camera vendor + string model_name = 2; // Name of the camera model + string firmware_version = + 3; // Camera firmware version in major[.minor[.patch[.dev]]] format + float focal_length_mm = 4; // Focal length + float horizontal_sensor_size_mm = 5; // Horizontal sensor size + float vertical_sensor_size_mm = 6; // Vertical sensor size + 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) + repeated CameraCapFlags camera_cap_flags = + 12; // Camera capability flags (Array) } diff --git a/protos/camera_server/camera_server.proto b/protos/camera_server/camera_server.proto index a8283dcd..7b444209 100644 --- a/protos/camera_server/camera_server.proto +++ b/protos/camera_server/camera_server.proto @@ -12,8 +12,8 @@ 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; } - // Sets video streaming settings. - rpc SetVideoStreaming(SetVideoStreamingRequest) returns(SetVideoStreamingResponse) { option (mavsdk.options.async_type) = SYNC; } + // Sets video stream info. + rpc SetVideoStreamInfo(SetVideoStreamInfoRequest) returns(SetVideoStreamInfoResponse) { option (mavsdk.options.async_type) = SYNC; } // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. rpc SetInProgress(SetInProgressRequest) returns(SetInProgressResponse) { option (mavsdk.options.async_type) = SYNC; } @@ -87,11 +87,11 @@ message SetInformationResponse { CameraServerResult camera_server_result = 1; } -message SetVideoStreamingRequest { - VideoStreaming video_streaming = 1; // information about the video stream +message SetVideoStreamInfoRequest { + repeated VideoStreamInfo video_stream_infos = 1; // Video stream infos } -message SetVideoStreamingResponse { +message SetVideoStreamInfoResponse { CameraServerResult camera_server_result = 1; } @@ -236,6 +236,35 @@ enum CameraFeedback { // Type to represent a camera information. message Information { + enum CameraCapFlags { + CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 0; // Camera is able to record video + CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 1; // Camera is able to capture images + CAMERA_CAP_FLAGS_HAS_MODES = + 2; // Camera has separate Video and Image/Photo modes + // (MAV_CMD_SET_CAMERA_MODE) + CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = + 3; // Camera can capture images while in video mode + CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = + 4; // Camera can capture videos while in Photo/Image mode + CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = + 5; // Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE) + CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = + 6; // Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM) + CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = + 7; // Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS) + CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = + 8; // Camera has video streaming capabilities (request + // VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video + // streaming info) + CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = + 9; // Camera supports tracking of a point on the camera view. + CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = + 10; // Camera supports tracking of a selection rectangle on the + // camera view. + CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = + 11; // Camera supports tracking geo status + // (CAMERA_TRACKING_GEO_STATUS). + }; string vendor_name = 1; // Name of the camera vendor string model_name = 2; // Name of the camera model string firmware_version = 3; // Camera firmware version in major[.minor[.patch[.dev]]] format @@ -247,12 +276,39 @@ message Information { 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) -} + repeated CameraCapFlags camera_cap_flags = 12; // Camera capability flags +} + +// 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 + } -// Type to represent video streaming settings -message VideoStreaming { - bool has_rtsp_server = 1; // True if the capture was successful - string rtsp_uri = 2; // RTSP URI (e.g. rtsp://192.168.1.42:8554/live) + int32 stream_id = 1; // stream unique id + VideoStreamSettings settings = 2; // Video stream settings + VideoStreamStatus status = 3; // Current status of video streaming + VideoStreamSpectrum spectrum = 4; // Light-spectrum of the video stream } // Position type in global coordinates.