From 02853b263818f61fa381a16ae6a6fad95aba147f Mon Sep 17 00:00:00 2001 From: tbago Date: Fri, 23 Feb 2024 11:07:12 +0800 Subject: [PATCH 1/3] Add more video streaming info * unify the camera and camera server stream info; * support multi camera video stream info; * add camera video stream info usage example; --- examples/camera_server/camera_client.cpp | 8 + examples/camera_server/camera_server.cpp | 39 + src/mavsdk/plugins/camera/camera.cpp | 7 +- src/mavsdk/plugins/camera/camera_impl.cpp | 124 +- src/mavsdk/plugins/camera/camera_impl.h | 6 +- .../camera/include/plugins/camera/camera.h | 11 +- .../plugins/camera_server/camera_server.cpp | 81 +- .../camera_server/camera_server_impl.cpp | 127 +- .../camera_server/camera_server_impl.h | 7 +- .../plugins/camera_server/camera_server.h | 86 +- .../src/generated/camera/camera.pb.cc | 550 +++--- .../src/generated/camera/camera.pb.h | 206 +-- .../camera_server/camera_server.grpc.pb.cc | 34 +- .../camera_server/camera_server.grpc.pb.h | 132 +- .../camera_server/camera_server.pb.cc | 1619 +++++++++++------ .../camera_server/camera_server.pb.h | 1217 ++++++++++--- .../src/plugins/camera/camera_service_impl.h | 12 +- .../camera_server_service_impl.h | 167 +- .../test/camera_service_impl_test.cpp | 19 +- 19 files changed, 2995 insertions(+), 1457 deletions(-) diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index 6dda0fdc2e..a99be8c2f6 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -50,6 +50,14 @@ int main(int argc, const char* argv[]) std::cout << info << std::endl; }); + camera.subscribe_video_stream_info( + [](std::vector video_stream_infos) { + std::cout << "Camera Video stream information:" << std::endl; + for (auto& stream_info : video_stream_infos) { + std::cout << stream_info << std::endl; + } + }); + camera.subscribe_status([](mavsdk::Camera::Status status) { std::cout << "Camera status:" << std::endl; std::cout << status << std::endl; diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index c7d8fa4f20..99a26fdea9 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -6,6 +6,7 @@ #include static void subscribe_camera_operation(mavsdk::CameraServer& camera_server); +static void SetVideoStreamInfo(mavsdk::CameraServer& camera_server); int main(int argc, char** argv) { @@ -44,6 +45,9 @@ int main(int argc, char** argv) .definition_file_uri = "", // TODO: implement this using MAVLink FTP }); + // set video stream info + SetVideoStreamInfo(camera_server); + if (ret != mavsdk::CameraServer::Result::Success) { std::cerr << "Failed to set camera info, exiting" << std::endl; return 2; @@ -175,4 +179,39 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) std::cout << "reset camera settings" << std::endl; camera_server.respond_reset_settings(mavsdk::CameraServer::CameraFeedback::Ok); }); +} + +static void SetVideoStreamInfo(mavsdk::CameraServer& camera_server) +{ + mavsdk::CameraServer::VideoStreamInfo normal_video_stream; + normal_video_stream.stream_id = 1; + + normal_video_stream.settings.frame_rate_hz = 60.0; + normal_video_stream.settings.horizontal_resolution_pix = 1920; + normal_video_stream.settings.vertical_resolution_pix = 1080; + normal_video_stream.settings.bit_rate_b_s = 4 * 1024 * 1024; + normal_video_stream.settings.rotation_deg = 1; + normal_video_stream.settings.uri = "rtsp://192.168.0.1/live"; + normal_video_stream.settings.horizontal_fov_deg = 1; + normal_video_stream.status = + mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus::InProgress; + normal_video_stream.spectrum = + mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::VisibleLight; + + mavsdk::CameraServer::VideoStreamInfo infrared_video_stream; + infrared_video_stream.stream_id = 2; + + infrared_video_stream.settings.frame_rate_hz = 24.0; + infrared_video_stream.settings.horizontal_resolution_pix = 1280; + infrared_video_stream.settings.vertical_resolution_pix = 720; + infrared_video_stream.settings.bit_rate_b_s = 4 * 1024; + infrared_video_stream.settings.rotation_deg = 2; + infrared_video_stream.settings.uri = "rtsp://192.168.0.1/live2"; + infrared_video_stream.settings.horizontal_fov_deg = 2; + infrared_video_stream.status = + mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus::NotRunning; + infrared_video_stream.spectrum = + mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::Infrared; + + auto ret = camera_server.set_video_stream_info({normal_video_stream, infrared_video_stream}); } \ No newline at end of file diff --git a/src/mavsdk/plugins/camera/camera.cpp b/src/mavsdk/plugins/camera/camera.cpp index e7e9126d57..2b51cb7090 100644 --- a/src/mavsdk/plugins/camera/camera.cpp +++ b/src/mavsdk/plugins/camera/camera.cpp @@ -162,7 +162,7 @@ void Camera::unsubscribe_video_stream_info(VideoStreamInfoHandle handle) _impl->unsubscribe_video_stream_info(handle); } -Camera::VideoStreamInfo Camera::video_stream_info() const +std::vector Camera::video_stream_info() const { return _impl->video_stream_info(); } @@ -437,14 +437,15 @@ std::ostream& operator<<( } bool operator==(const Camera::VideoStreamInfo& lhs, const Camera::VideoStreamInfo& rhs) { - return (rhs.settings == lhs.settings) && (rhs.status == lhs.status) && - (rhs.spectrum == lhs.spectrum); + return (rhs.stream_id == lhs.stream_id) && (rhs.settings == lhs.settings) && + (rhs.status == lhs.status) && (rhs.spectrum == lhs.spectrum); } std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo const& video_stream_info) { str << std::setprecision(15); str << "video_stream_info:" << '\n' << "{\n"; + str << " stream_id: " << video_stream_info.stream_id << '\n'; str << " settings: " << video_stream_info.settings << '\n'; str << " status: " << video_stream_info.status << '\n'; str << " spectrum: " << video_stream_info.spectrum << '\n'; diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index e7a9d250d1..4476834123 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -506,11 +506,6 @@ Camera::Result CameraImpl::stop_video() { auto cmd_stop_video = make_command_stop_video(); - { - std::lock_guard lock(_video_stream_info.mutex); - _video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning; - } - return camera_result_from_command_result(_system_impl->send_command(cmd_stop_video)); } @@ -626,9 +621,14 @@ Camera::Result CameraImpl::start_video_streaming(int32_t stream_id) { std::lock_guard lock(_video_stream_info.mutex); - if (_video_stream_info.available && - _video_stream_info.data.status == Camera::VideoStreamInfo::VideoStreamStatus::InProgress) { - return Camera::Result::InProgress; + if (_video_stream_info.available) { + for (auto& video_stream_info : _video_stream_info.data) { + if (video_stream_info.stream_id == stream_id && + video_stream_info.status == + Camera::VideoStreamInfo::VideoStreamStatus::InProgress) { + return Camera::Result::InProgress; + } + } } // TODO Check whether we're in video mode @@ -654,7 +654,13 @@ Camera::Result CameraImpl::stop_video_streaming(int32_t stream_id) { std::lock_guard lock(_video_stream_info.mutex); // TODO: check if we can/should do that. - _video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning; + // TODO: the better way is use the video streaming subscribe to get the current + // stream status + for (auto& video_stream_info : _video_stream_info.data) { + if (video_stream_info.stream_id == stream_id) { + video_stream_info.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning; + } + } } return result; } @@ -665,7 +671,7 @@ void CameraImpl::request_video_stream_info() _system_impl->send_command_async(make_command_request_video_stream_status(), nullptr); } -Camera::VideoStreamInfo CameraImpl::video_stream_info() +std::vector CameraImpl::video_stream_info() { std::lock_guard lock(_video_stream_info.mutex); @@ -1054,9 +1060,9 @@ void CameraImpl::process_camera_image_captured(const mavlink_message_t& message) capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); }); if (_capture_info.last_advertised_image_index != -1) { - // Save captured indices that have been dropped to request later, however, don't - // do it from the very beginning as there might be many photos from a previous - // time that we don't want to request. + // Save captured indices that have been dropped to request later, however, + // don't do it from the very beginning as there might be many photos from a + // previous time that we don't want to request. for (int i = _capture_info.last_advertised_image_index + 1; i < capture_info.index; ++i) { if (_capture_info.missing_image_retries.find(i) == @@ -1259,24 +1265,41 @@ void CameraImpl::process_video_information(const mavlink_message_t& message) { std::lock_guard lock(_video_stream_info.mutex); - // TODO: use stream_id and count - _video_stream_info.data.status = + mavsdk::Camera::VideoStreamInfo video_stream_info; + video_stream_info.stream_id = received_video_info.stream_id; + + video_stream_info.status = (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ? Camera::VideoStreamInfo::VideoStreamStatus::InProgress : Camera::VideoStreamInfo::VideoStreamStatus::NotRunning); - _video_stream_info.data.spectrum = + video_stream_info.spectrum = (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ? Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared : Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight); - auto& video_stream_info = _video_stream_info.data.settings; - video_stream_info.frame_rate_hz = received_video_info.framerate; - video_stream_info.horizontal_resolution_pix = received_video_info.resolution_h; - video_stream_info.vertical_resolution_pix = received_video_info.resolution_v; - video_stream_info.bit_rate_b_s = received_video_info.bitrate; - video_stream_info.rotation_deg = received_video_info.rotation; - video_stream_info.horizontal_fov_deg = static_cast(received_video_info.hfov); - video_stream_info.uri = received_video_info.uri; + video_stream_info.settings.frame_rate_hz = received_video_info.framerate; + video_stream_info.settings.horizontal_resolution_pix = received_video_info.resolution_h; + video_stream_info.settings.vertical_resolution_pix = received_video_info.resolution_v; + video_stream_info.settings.bit_rate_b_s = received_video_info.bitrate; + video_stream_info.settings.rotation_deg = received_video_info.rotation; + video_stream_info.settings.horizontal_fov_deg = + static_cast(received_video_info.hfov); + video_stream_info.settings.uri = received_video_info.uri; + + bool found = false; + for (auto& it : _video_stream_info.data) { + if (it.stream_id == received_video_info.stream_id) { // video stream info already exits + // copy video stream info + it = video_stream_info; + found = true; + break; + } + } + if (!found) { + _video_stream_info.data.emplace_back(video_stream_info); + } + + LogDebug() << "Found " << _video_stream_info.data.size() << " video stream"; _video_stream_info.available = true; } @@ -1289,27 +1312,32 @@ void CameraImpl::process_video_stream_status(const mavlink_message_t& message) mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status); { std::lock_guard lock(_video_stream_info.mutex); - _video_stream_info.data.status = - (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ? - Camera::VideoStreamInfo::VideoStreamStatus::InProgress : - Camera::VideoStreamInfo::VideoStreamStatus::NotRunning); - _video_stream_info.data.spectrum = - (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ? - Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared : - Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight); - - auto& video_stream_info = _video_stream_info.data.settings; - video_stream_info.frame_rate_hz = received_video_stream_status.framerate; - video_stream_info.horizontal_resolution_pix = received_video_stream_status.resolution_h; - video_stream_info.vertical_resolution_pix = received_video_stream_status.resolution_v; - video_stream_info.bit_rate_b_s = received_video_stream_status.bitrate; - video_stream_info.rotation_deg = received_video_stream_status.rotation; - video_stream_info.horizontal_fov_deg = - static_cast(received_video_stream_status.hfov); - _video_stream_info.available = true; + for (auto& video_stream_info : _video_stream_info.data) { + if (video_stream_info.stream_id == received_video_stream_status.stream_id) { + video_stream_info.status = + (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ? + Camera::VideoStreamInfo::VideoStreamStatus::InProgress : + Camera::VideoStreamInfo::VideoStreamStatus::NotRunning); + video_stream_info.spectrum = + (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ? + Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared : + Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight); + + video_stream_info.settings.frame_rate_hz = received_video_stream_status.framerate; + video_stream_info.settings.horizontal_resolution_pix = + received_video_stream_status.resolution_h; + video_stream_info.settings.vertical_resolution_pix = + received_video_stream_status.resolution_v; + video_stream_info.settings.bit_rate_b_s = received_video_stream_status.bitrate; + video_stream_info.settings.rotation_deg = received_video_stream_status.rotation; + video_stream_info.settings.horizontal_fov_deg = + static_cast(received_video_stream_status.hfov); + + _video_stream_info.available = true; + notify_video_stream_info(); + } + } } - - notify_video_stream_info(); } void CameraImpl::process_flight_information(const mavlink_message_t& message) @@ -1602,7 +1630,8 @@ void CameraImpl::set_option_async( [temp_callback]() { temp_callback(Camera::Result::Success); }); } - // FIXME: We are already holding the lock when this lambda is run and need to + // FIXME: We are already holding the lock when this lambda is run and need + // to // schedule the refresh_params() for later. // We (ab)use the thread pool for the user callbacks for this. _system_impl->call_user_callback([this]() { refresh_params(); }); @@ -2064,8 +2093,9 @@ void CameraImpl::list_photos_async( std::unique_lock capture_request_lock(_captured_request_mutex); for (int i = start_index; i < _status.image_count; i++) { - // In case the vehicle sends capture info, but not those we are asking, we do not - // want to loop infinitely. The safety_count is here to abort if this happens. + // In case the vehicle sends capture info, but not those we are asking, we do + // not want to loop infinitely. The safety_count is here to abort if this + // happens. auto safety_count = 0; const auto safety_count_boundary = 10; diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index 8ff928d65f..02cb9e6446 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -47,7 +47,7 @@ class CameraImpl : public PluginImplBase { std::pair get_video_stream_info(); - Camera::VideoStreamInfo video_stream_info(); + std::vector video_stream_info(); Camera::VideoStreamInfoHandle subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback); void unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle); @@ -254,10 +254,10 @@ class CameraImpl : public PluginImplBase { struct { std::mutex mutex{}; - Camera::VideoStreamInfo data{}; + std::vector data{}; bool available{false}; void* call_every_cookie{nullptr}; - CallbackList subscription_callbacks{}; + CallbackList> subscription_callbacks{}; } _video_stream_info{}; struct { diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index 57bdaa5937..6a241d92f7 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -298,6 +298,7 @@ class Camera : public PluginBase { std::ostream& str, Camera::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum); + int32_t stream_id{}; /**< @brief stream unique id */ VideoStreamSettings settings{}; /**< @brief Video stream settings */ VideoStreamStatus status{}; /**< @brief Current status of video streaming */ VideoStreamSpectrum spectrum{}; /**< @brief Light-spectrum of the video stream */ @@ -704,12 +705,12 @@ class Camera : public PluginBase { /** * @brief Callback type for subscribe_video_stream_info. */ - using VideoStreamInfoCallback = std::function; + using VideoStreamInfoCallback = std::function)>; /** * @brief Handle type for subscribe_video_stream_info. */ - using VideoStreamInfoHandle = Handle; + using VideoStreamInfoHandle = Handle>; /** * @brief Subscribe to video stream info updates. @@ -722,11 +723,11 @@ class Camera : public PluginBase { void unsubscribe_video_stream_info(VideoStreamInfoHandle handle); /** - * @brief Poll for 'VideoStreamInfo' (blocking). + * @brief Poll for 'std::vector' (blocking). * - * @return One VideoStreamInfo update. + * @return One std::vector update. */ - VideoStreamInfo video_stream_info() const; + std::vector video_stream_info() const; /** * @brief Callback type for subscribe_capture_info. diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index ef75fa7cc0..45ba39cf4e 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -11,7 +11,8 @@ namespace mavsdk { using Information = CameraServer::Information; -using VideoStreaming = CameraServer::VideoStreaming; +using VideoStreamSettings = CameraServer::VideoStreamSettings; +using VideoStreamInfo = CameraServer::VideoStreamInfo; using Position = CameraServer::Position; using Quaternion = CameraServer::Quaternion; using CaptureInfo = CameraServer::CaptureInfo; @@ -31,9 +32,10 @@ CameraServer::Result CameraServer::set_information(Information information) cons return _impl->set_information(information); } -CameraServer::Result CameraServer::set_video_streaming(VideoStreaming video_streaming) const +CameraServer::Result +CameraServer::set_video_stream_info(std::vector video_stream_infos) const { - return _impl->set_video_streaming(video_streaming); + return _impl->set_video_stream_info(video_stream_infos); } CameraServer::Result CameraServer::set_in_progress(bool in_progress) const @@ -242,17 +244,78 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Information const& inf return str; } -bool operator==(const CameraServer::VideoStreaming& lhs, const CameraServer::VideoStreaming& rhs) +bool operator==( + const CameraServer::VideoStreamSettings& lhs, const CameraServer::VideoStreamSettings& rhs) +{ + return ((std::isnan(rhs.frame_rate_hz) && std::isnan(lhs.frame_rate_hz)) || + rhs.frame_rate_hz == lhs.frame_rate_hz) && + (rhs.horizontal_resolution_pix == lhs.horizontal_resolution_pix) && + (rhs.vertical_resolution_pix == lhs.vertical_resolution_pix) && + (rhs.bit_rate_b_s == lhs.bit_rate_b_s) && (rhs.rotation_deg == lhs.rotation_deg) && + (rhs.uri == lhs.uri) && + ((std::isnan(rhs.horizontal_fov_deg) && std::isnan(lhs.horizontal_fov_deg)) || + rhs.horizontal_fov_deg == lhs.horizontal_fov_deg); +} + +std::ostream& +operator<<(std::ostream& str, CameraServer::VideoStreamSettings const& video_stream_settings) +{ + str << std::setprecision(15); + str << "video_stream_settings:" << '\n' << "{\n"; + str << " frame_rate_hz: " << video_stream_settings.frame_rate_hz << '\n'; + str << " horizontal_resolution_pix: " << video_stream_settings.horizontal_resolution_pix + << '\n'; + str << " vertical_resolution_pix: " << video_stream_settings.vertical_resolution_pix << '\n'; + str << " bit_rate_b_s: " << video_stream_settings.bit_rate_b_s << '\n'; + str << " rotation_deg: " << video_stream_settings.rotation_deg << '\n'; + str << " uri: " << video_stream_settings.uri << '\n'; + str << " horizontal_fov_deg: " << video_stream_settings.horizontal_fov_deg << '\n'; + str << '}'; + return str; +} + +std::ostream& operator<<( + std::ostream& str, CameraServer::VideoStreamInfo::VideoStreamStatus const& video_stream_status) +{ + switch (video_stream_status) { + case CameraServer::VideoStreamInfo::VideoStreamStatus::NotRunning: + return str << "Not Running"; + case CameraServer::VideoStreamInfo::VideoStreamStatus::InProgress: + return str << "In Progress"; + default: + return str << "Unknown"; + } +} + +std::ostream& operator<<( + std::ostream& str, + CameraServer::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum) +{ + switch (video_stream_spectrum) { + case CameraServer::VideoStreamInfo::VideoStreamSpectrum::Unknown: + return str << "Unknown"; + case CameraServer::VideoStreamInfo::VideoStreamSpectrum::VisibleLight: + return str << "Visible Light"; + case CameraServer::VideoStreamInfo::VideoStreamSpectrum::Infrared: + return str << "Infrared"; + default: + return str << "Unknown"; + } +} +bool operator==(const CameraServer::VideoStreamInfo& lhs, const CameraServer::VideoStreamInfo& rhs) { - return (rhs.has_rtsp_server == lhs.has_rtsp_server) && (rhs.rtsp_uri == lhs.rtsp_uri); + return (rhs.stream_id == lhs.stream_id) && (rhs.settings == lhs.settings) && + (rhs.status == lhs.status) && (rhs.spectrum == lhs.spectrum); } -std::ostream& operator<<(std::ostream& str, CameraServer::VideoStreaming const& video_streaming) +std::ostream& operator<<(std::ostream& str, CameraServer::VideoStreamInfo const& video_stream_info) { str << std::setprecision(15); - str << "video_streaming:" << '\n' << "{\n"; - str << " has_rtsp_server: " << video_streaming.has_rtsp_server << '\n'; - str << " rtsp_uri: " << video_streaming.rtsp_uri << '\n'; + str << "video_stream_info:" << '\n' << "{\n"; + str << " stream_id: " << video_stream_info.stream_id << '\n'; + str << " settings: " << video_stream_info.settings << '\n'; + str << " status: " << video_stream_info.status << '\n'; + str << " spectrum: " << video_stream_info.spectrum << '\n'; str << '}'; return str; } diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 293d661c68..b1001b2733 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -186,13 +186,13 @@ CameraServer::Result CameraServerImpl::set_information(CameraServer::Information return CameraServer::Result::Success; } -CameraServer::Result -CameraServerImpl::set_video_streaming(CameraServer::VideoStreaming video_streaming) +CameraServer::Result CameraServerImpl::set_video_stream_info( + std::vector video_stream_infos) { - // TODO: validate uri length + // TODO: validate video stream infos - _is_video_streaming_set = true; - _video_streaming = video_streaming; + _is_video_stream_info_set = true; + _video_stream_infos = video_stream_infos; return CameraServer::Result::Success; } @@ -835,7 +835,7 @@ std::optional CameraServerImpl::process_camera_informatio capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES; } - if (_is_video_streaming_set) { + if (_is_video_stream_info_set) { capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; } @@ -1326,43 +1326,51 @@ std::optional CameraServerImpl::process_video_stream_info UNUSED(stream_id); - if (_is_video_streaming_set) { - auto command_ack = _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); - _server_component_impl->send_command_ack(command_ack); - LogDebug() << "sent video streaming ack"; - - const char name[32] = ""; + if (!_is_video_stream_info_set) { + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } - _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri)); + auto command_ack = + _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + LogDebug() << "sent video stream information ack"; + + // loop send video stream info + for (auto& video_stream_info : _video_stream_infos) { + uint16_t flags = 0; + if (video_stream_info.status == + CameraServer::VideoStreamInfo::VideoStreamStatus::InProgress) { + flags |= VIDEO_STREAM_STATUS_FLAGS_RUNNING; + } + if (video_stream_info.spectrum == + CameraServer::VideoStreamInfo::VideoStreamSpectrum::Infrared) { + flags |= VIDEO_STREAM_STATUS_FLAGS_THERMAL; + } mavlink_message_t msg{}; mavlink_msg_video_stream_information_pack( _server_component_impl->get_own_system_id(), _server_component_impl->get_own_component_id(), &msg, - 0, // Stream id - 0, // Count - VIDEO_STREAM_TYPE_RTSP, - VIDEO_STREAM_STATUS_FLAGS_RUNNING, - 0, // famerate - 0, // resolution horizontal - 0, // resolution vertical - 0, // bitrate - 0, // rotation - 0, // horizontal field of view - name, - _video_streaming.rtsp_uri.c_str()); + video_stream_info.stream_id, + 1, + 0, + flags, + video_stream_info.settings.frame_rate_hz, + video_stream_info.settings.horizontal_resolution_pix, + video_stream_info.settings.vertical_resolution_pix, + video_stream_info.settings.bit_rate_b_s, + video_stream_info.settings.rotation_deg, + video_stream_info.settings.horizontal_fov_deg, + "", + video_stream_info.settings.uri.c_str()); _server_component_impl->send_message(msg); - - // Ack already sent. - return std::nullopt; - - } else { - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } + + // Ack already sent. + return std::nullopt; } std::optional CameraServerImpl::process_video_stream_status_request( @@ -1372,7 +1380,7 @@ std::optional CameraServerImpl::process_video_stream_stat UNUSED(stream_id); - if (!_is_video_streaming_set) { + if (!_is_video_stream_info_set) { return _server_component_impl->make_command_ack_message( command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } @@ -1380,23 +1388,40 @@ std::optional CameraServerImpl::process_video_stream_stat auto command_ack = _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - LogDebug() << "sent video streaming ack"; - - mavlink_message_t msg{}; - mavlink_msg_video_stream_status_pack( - _server_component_impl->get_own_system_id(), - _server_component_impl->get_own_component_id(), - &msg, - 0, // Stream id - VIDEO_STREAM_STATUS_FLAGS_RUNNING, - 0, // framerate - 0, // resolution horizontal - 0, // resolution vertical - 0, // bitrate - 0, // rotation - 0 // horizontal field of view - ); - _server_component_impl->send_message(msg); + LogDebug() << "sent video stream status ack"; + + // loop send video stream info + for (auto& video_stream_info : _video_stream_infos) { + uint16_t flags = 0; + if (video_stream_info.status == + CameraServer::VideoStreamInfo::VideoStreamStatus::InProgress) { + flags |= VIDEO_STREAM_STATUS_FLAGS_RUNNING; + } + if (video_stream_info.spectrum == + CameraServer::VideoStreamInfo::VideoStreamSpectrum::Infrared) { + flags |= VIDEO_STREAM_STATUS_FLAGS_THERMAL; + } + + mavlink_message_t msg{}; + mavlink_msg_video_stream_information_pack( + _server_component_impl->get_own_system_id(), + _server_component_impl->get_own_component_id(), + &msg, + video_stream_info.stream_id, + 1, + 0, + flags, + video_stream_info.settings.frame_rate_hz, + video_stream_info.settings.horizontal_resolution_pix, + video_stream_info.settings.vertical_resolution_pix, + video_stream_info.settings.bit_rate_b_s, + video_stream_info.settings.rotation_deg, + video_stream_info.settings.horizontal_fov_deg, + "", + video_stream_info.settings.uri.c_str()); + + _server_component_impl->send_message(msg); + } // ack was already sent return std::nullopt; diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 90dc8698a0..0d613f0b1b 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -15,7 +15,8 @@ class CameraServerImpl : public ServerPluginImplBase { void deinit() override; CameraServer::Result set_information(CameraServer::Information information); - CameraServer::Result set_video_streaming(CameraServer::VideoStreaming video_streaming); + CameraServer::Result + set_video_stream_info(std::vector video_stream_infos); CameraServer::Result set_in_progress(bool in_progress); CameraServer::TakePhotoHandle @@ -90,8 +91,8 @@ class CameraServerImpl : public ServerPluginImplBase { bool _is_information_set{}; CameraServer::Information _information{}; - bool _is_video_streaming_set{}; - CameraServer::VideoStreaming _video_streaming{}; + bool _is_video_stream_info_set{}; + std::vector _video_stream_infos; CameraServer::CaptureStatus _capture_status{}; diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index e92f0661e1..40e7ca91a8 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -116,28 +116,94 @@ class CameraServer : public ServerPluginBase { operator<<(std::ostream& str, CameraServer::Information const& information); /** - * @brief Type to represent video streaming settings + * @brief Type for video stream settings. + */ + struct VideoStreamSettings { + float frame_rate_hz{}; /**< @brief Frames per second */ + uint32_t horizontal_resolution_pix{}; /**< @brief Horizontal resolution (in pixels) */ + uint32_t vertical_resolution_pix{}; /**< @brief Vertical resolution (in pixels) */ + uint32_t bit_rate_b_s{}; /**< @brief Bit rate (in bits per second) */ + uint32_t rotation_deg{}; /**< @brief Video image rotation (clockwise, 0-359 degrees) */ + std::string uri{}; /**< @brief Video stream URI */ + float horizontal_fov_deg{}; /**< @brief Horizontal fov in degrees */ + }; + + /** + * @brief Equal operator to compare two `CameraServer::VideoStreamSettings` objects. + * + * @return `true` if items are equal. */ - struct VideoStreaming { - bool has_rtsp_server{}; /**< @brief True if the capture was successful */ - std::string rtsp_uri{}; /**< @brief RTSP URI (e.g. rtsp://192.168.1.42:8554/live) */ + friend bool operator==( + const CameraServer::VideoStreamSettings& lhs, const CameraServer::VideoStreamSettings& rhs); + + /** + * @brief Stream operator to print information about a `CameraServer::VideoStreamSettings`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, CameraServer::VideoStreamSettings const& video_stream_settings); + + /** + * @brief Information about the video stream. + */ + struct VideoStreamInfo { + /** + * @brief Video stream status type. + */ + enum class VideoStreamStatus { + NotRunning, /**< @brief Video stream is not running. */ + InProgress, /**< @brief Video stream is running. */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::VideoStreamStatus`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<( + std::ostream& str, + CameraServer::VideoStreamInfo::VideoStreamStatus const& video_stream_status); + + /** + * @brief Video stream light spectrum type + */ + enum class VideoStreamSpectrum { + Unknown, /**< @brief Unknown. */ + VisibleLight, /**< @brief Visible light. */ + Infrared, /**< @brief Infrared. */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::VideoStreamSpectrum`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<( + std::ostream& str, + CameraServer::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum); + + int32_t stream_id{}; /**< @brief stream unique id */ + VideoStreamSettings settings{}; /**< @brief Video stream settings */ + VideoStreamStatus status{}; /**< @brief Current status of video streaming */ + VideoStreamSpectrum spectrum{}; /**< @brief Light-spectrum of the video stream */ }; /** - * @brief Equal operator to compare two `CameraServer::VideoStreaming` objects. + * @brief Equal operator to compare two `CameraServer::VideoStreamInfo` objects. * * @return `true` if items are equal. */ friend bool - operator==(const CameraServer::VideoStreaming& lhs, const CameraServer::VideoStreaming& rhs); + operator==(const CameraServer::VideoStreamInfo& lhs, const CameraServer::VideoStreamInfo& rhs); /** - * @brief Stream operator to print information about a `CameraServer::VideoStreaming`. + * @brief Stream operator to print information about a `CameraServer::VideoStreamInfo`. * * @return A reference to the stream. */ friend std::ostream& - operator<<(std::ostream& str, CameraServer::VideoStreaming const& video_streaming); + operator<<(std::ostream& str, CameraServer::VideoStreamInfo const& video_stream_info); /** * @brief Position type in global coordinates. @@ -395,13 +461,13 @@ class CameraServer : public ServerPluginBase { Result set_information(Information information) const; /** - * @brief Sets video streaming settings. + * @brief Sets video stream info. * * This function is blocking. * * @return Result of request. */ - Result set_video_streaming(VideoStreaming video_streaming) const; + Result set_video_stream_info(std::vector video_stream_infos) const; /** * @brief Sets image capture in progress status flags. This should be set to true when the diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.cc b/src/mavsdk_server/src/generated/camera/camera.pb.cc index 6a42fa9005..5e0321c047 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.pb.cc @@ -533,6 +533,7 @@ inline constexpr VideoStreamInfo::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, settings_{nullptr}, + stream_id_{0}, status_{static_cast< ::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamStatus >(0)}, spectrum_{static_cast< ::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamSpectrum >(0)} {} @@ -916,8 +917,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr VideoStreamInfoResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - video_stream_info_{nullptr} {} + : video_stream_infos_{}, + _cached_size_{0} {} template PROTOBUF_CONSTEXPR VideoStreamInfoResponse::VideoStreamInfoResponse(::_pbi::ConstantInitialized) @@ -1306,7 +1307,7 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfoResponse, _impl_._has_bits_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfoResponse, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -1314,8 +1315,7 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfoResponse, _impl_.video_stream_info_), - 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfoResponse, _impl_.video_stream_infos_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SubscribeCaptureInfoRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -1574,9 +1574,11 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfo, _impl_.stream_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfo, _impl_.settings_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfo, _impl_.status_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfo, _impl_.spectrum_), + ~0u, 0, ~0u, ~0u, @@ -1680,37 +1682,37 @@ static const ::_pbi::MigrationSchema {205, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeModeRequest)}, {213, -1, -1, sizeof(::mavsdk::rpc::camera::ModeResponse)}, {222, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest)}, - {230, 239, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfoResponse)}, - {240, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCaptureInfoRequest)}, - {248, 257, -1, sizeof(::mavsdk::rpc::camera::CaptureInfoResponse)}, - {258, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeStatusRequest)}, - {266, 275, -1, sizeof(::mavsdk::rpc::camera::StatusResponse)}, - {276, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest)}, - {284, -1, -1, sizeof(::mavsdk::rpc::camera::CurrentSettingsResponse)}, - {293, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest)}, - {301, -1, -1, sizeof(::mavsdk::rpc::camera::PossibleSettingOptionsResponse)}, - {310, 319, -1, sizeof(::mavsdk::rpc::camera::SetSettingRequest)}, - {320, 329, -1, sizeof(::mavsdk::rpc::camera::SetSettingResponse)}, - {330, 339, -1, sizeof(::mavsdk::rpc::camera::GetSettingRequest)}, - {340, 350, -1, sizeof(::mavsdk::rpc::camera::GetSettingResponse)}, - {352, -1, -1, sizeof(::mavsdk::rpc::camera::FormatStorageRequest)}, - {361, 370, -1, sizeof(::mavsdk::rpc::camera::FormatStorageResponse)}, - {371, 380, -1, sizeof(::mavsdk::rpc::camera::SelectCameraResponse)}, - {381, -1, -1, sizeof(::mavsdk::rpc::camera::SelectCameraRequest)}, - {390, -1, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsRequest)}, - {398, 407, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsResponse)}, - {408, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, - {418, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, - {430, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, - {442, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, - {453, 468, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, - {475, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, - {490, 501, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, - {504, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, - {522, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, - {532, 544, -1, sizeof(::mavsdk::rpc::camera::Setting)}, - {548, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, - {560, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, + {230, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfoResponse)}, + {239, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCaptureInfoRequest)}, + {247, 256, -1, sizeof(::mavsdk::rpc::camera::CaptureInfoResponse)}, + {257, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeStatusRequest)}, + {265, 274, -1, sizeof(::mavsdk::rpc::camera::StatusResponse)}, + {275, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest)}, + {283, -1, -1, sizeof(::mavsdk::rpc::camera::CurrentSettingsResponse)}, + {292, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest)}, + {300, -1, -1, sizeof(::mavsdk::rpc::camera::PossibleSettingOptionsResponse)}, + {309, 318, -1, sizeof(::mavsdk::rpc::camera::SetSettingRequest)}, + {319, 328, -1, sizeof(::mavsdk::rpc::camera::SetSettingResponse)}, + {329, 338, -1, sizeof(::mavsdk::rpc::camera::GetSettingRequest)}, + {339, 349, -1, sizeof(::mavsdk::rpc::camera::GetSettingResponse)}, + {351, -1, -1, sizeof(::mavsdk::rpc::camera::FormatStorageRequest)}, + {360, 369, -1, sizeof(::mavsdk::rpc::camera::FormatStorageResponse)}, + {370, 379, -1, sizeof(::mavsdk::rpc::camera::SelectCameraResponse)}, + {380, -1, -1, sizeof(::mavsdk::rpc::camera::SelectCameraRequest)}, + {389, -1, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsRequest)}, + {397, 406, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsResponse)}, + {407, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, + {417, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, + {429, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, + {441, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, + {452, 467, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, + {474, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, + {489, 501, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, + {505, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, + {523, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, + {533, 545, -1, sizeof(::mavsdk::rpc::camera::Setting)}, + {549, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, + {561, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -1810,167 +1812,168 @@ const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_ "ra.Information\"\026\n\024SubscribeModeRequest\"5" "\n\014ModeResponse\022%\n\004mode\030\001 \001(\0162\027.mavsdk.rp" "c.camera.Mode\"!\n\037SubscribeVideoStreamInf" - "oRequest\"X\n\027VideoStreamInfoResponse\022=\n\021v" - "ideo_stream_info\030\001 \001(\0132\".mavsdk.rpc.came" - "ra.VideoStreamInfo\"\035\n\033SubscribeCaptureIn" - "foRequest\"K\n\023CaptureInfoResponse\0224\n\014capt" - "ure_info\030\001 \001(\0132\036.mavsdk.rpc.camera.Captu" - "reInfo\"\030\n\026SubscribeStatusRequest\"B\n\016Stat" - "usResponse\0220\n\rcamera_status\030\001 \001(\0132\031.mavs" - "dk.rpc.camera.Status\"!\n\037SubscribeCurrent" - "SettingsRequest\"O\n\027CurrentSettingsRespon" - "se\0224\n\020current_settings\030\001 \003(\0132\032.mavsdk.rp" - "c.camera.Setting\"(\n&SubscribePossibleSet" - "tingOptionsRequest\"\\\n\036PossibleSettingOpt" - "ionsResponse\022:\n\017setting_options\030\001 \003(\0132!." - "mavsdk.rpc.camera.SettingOptions\"@\n\021SetS" - "ettingRequest\022+\n\007setting\030\001 \001(\0132\032.mavsdk." - "rpc.camera.Setting\"L\n\022SetSettingResponse" - "\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.cam" - "era.CameraResult\"@\n\021GetSettingRequest\022+\n" - "\007setting\030\001 \001(\0132\032.mavsdk.rpc.camera.Setti" - "ng\"y\n\022GetSettingResponse\0226\n\rcamera_resul" - "t\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult" - "\022+\n\007setting\030\002 \001(\0132\032.mavsdk.rpc.camera.Se" - "tting\"*\n\024FormatStorageRequest\022\022\n\nstorage" - "_id\030\001 \001(\005\"O\n\025FormatStorageResponse\0226\n\rca" - "mera_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Ca" - "meraResult\"N\n\024SelectCameraResponse\0226\n\rca" - "mera_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Ca" - "meraResult\"(\n\023SelectCameraRequest\022\021\n\tcam" - "era_id\030\001 \001(\005\"\026\n\024ResetSettingsRequest\"O\n\025" - "ResetSettingsResponse\0226\n\rcamera_result\030\001" - " \001(\0132\037.mavsdk.rpc.camera.CameraResult\"\301\002" - "\n\014CameraResult\0226\n\006result\030\001 \001(\0162&.mavsdk." - "rpc.camera.CameraResult.Result\022\022\n\nresult" - "_str\030\002 \001(\t\"\344\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020" - "\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGR" - "ESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020" - "\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022" - "\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_" - "SYSTEM\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPPORTED\020" - "\t\"q\n\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rl" - "ongitude_deg\030\002 \001(\001\022\033\n\023absolute_altitude_" - "m\030\003 \001(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n\n" - "Quaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 " - "\001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n\010roll_deg" - "\030\001 \001(\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007yaw_deg\030\003 \001" - "(\002\"\377\001\n\013CaptureInfo\022-\n\010position\030\001 \001(\0132\033.m" - "avsdk.rpc.camera.Position\022:\n\023attitude_qu" - "aternion\030\002 \001(\0132\035.mavsdk.rpc.camera.Quate" - "rnion\022;\n\024attitude_euler_angle\030\003 \001(\0132\035.ma" - "vsdk.rpc.camera.EulerAngle\022\023\n\013time_utc_u" - "s\030\004 \001(\004\022\022\n\nis_success\030\005 \001(\010\022\r\n\005index\030\006 \001" - "(\005\022\020\n\010file_url\030\007 \001(\t\"\305\001\n\023VideoStreamSett" - "ings\022\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031horizonta" - "l_resolution_pix\030\002 \001(\r\022\037\n\027vertical_resol" - "ution_pix\030\003 \001(\r\022\024\n\014bit_rate_b_s\030\004 \001(\r\022\024\n" - "\014rotation_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032\n\022hori" - "zontal_fov_deg\030\007 \001(\002\"\302\003\n\017VideoStreamInfo" - "\0228\n\010settings\030\001 \001(\0132&.mavsdk.rpc.camera.V" - "ideoStreamSettings\022D\n\006status\030\002 \001(\01624.mav" - "sdk.rpc.camera.VideoStreamInfo.VideoStre" - "amStatus\022H\n\010spectrum\030\003 \001(\01626.mavsdk.rpc." - "camera.VideoStreamInfo.VideoStreamSpectr" - "um\"]\n\021VideoStreamStatus\022#\n\037VIDEO_STREAM_" - "STATUS_NOT_RUNNING\020\000\022#\n\037VIDEO_STREAM_STA" - "TUS_IN_PROGRESS\020\001\"\205\001\n\023VideoStreamSpectru" - "m\022!\n\035VIDEO_STREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#" - "VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n" - "\036VIDEO_STREAM_SPECTRUM_INFRARED\020\002\"\207\005\n\006St" - "atus\022\020\n\010video_on\030\001 \001(\010\022\031\n\021photo_interval" - "_on\030\002 \001(\010\022\030\n\020used_storage_mib\030\003 \001(\002\022\035\n\025a" - "vailable_storage_mib\030\004 \001(\002\022\031\n\021total_stor" - "age_mib\030\005 \001(\002\022\030\n\020recording_time_s\030\006 \001(\002\022" - "\031\n\021media_folder_name\030\007 \001(\t\022\?\n\016storage_st" - "atus\030\010 \001(\0162\'.mavsdk.rpc.camera.Status.St" - "orageStatus\022\022\n\nstorage_id\030\t \001(\r\022;\n\014stora" - "ge_type\030\n \001(\0162%.mavsdk.rpc.camera.Status" - ".StorageType\"\221\001\n\rStorageStatus\022 \n\034STORAG" - "E_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STAT" - "US_UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMA" - "TTED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003" - "\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN" - "\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAG" - "E_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n" - "\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER" - "\020\376\001\"7\n\006Option\022\021\n\toption_id\030\001 \001(\t\022\032\n\022opti" - "on_description\030\002 \001(\t\"w\n\007Setting\022\022\n\nsetti" - "ng_id\030\001 \001(\t\022\033\n\023setting_description\030\002 \001(\t" - "\022)\n\006option\030\003 \001(\0132\031.mavsdk.rpc.camera.Opt" - "ion\022\020\n\010is_range\030\004 \001(\010\"\177\n\016SettingOptions\022" - "\022\n\nsetting_id\030\001 \001(\t\022\033\n\023setting_descripti" - "on\030\002 \001(\t\022*\n\007options\030\003 \003(\0132\031.mavsdk.rpc.c" - "amera.Option\022\020\n\010is_range\030\004 \001(\010\"\325\001\n\013Infor" - "mation\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_nam" - "e\030\002 \001(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031hori" - "zontal_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_" - "sensor_size_mm\030\005 \001(\002\022 \n\030horizontal_resol" - "ution_px\030\006 \001(\r\022\036\n\026vertical_resolution_px" - "\030\007 \001(\r*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE" - "_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\002*F\n\013PhotosRange\022" - "\024\n\020PHOTOS_RANGE_ALL\020\000\022!\n\035PHOTOS_RANGE_SI" - "NCE_CONNECTION\020\0012\271\022\n\rCameraService\022R\n\007Pr" - "epare\022!.mavsdk.rpc.camera.PrepareRequest" - "\032\".mavsdk.rpc.camera.PrepareResponse\"\000\022X" - "\n\tTakePhoto\022#.mavsdk.rpc.camera.TakePhot" - "oRequest\032$.mavsdk.rpc.camera.TakePhotoRe" - "sponse\"\000\022s\n\022StartPhotoInterval\022,.mavsdk." - "rpc.camera.StartPhotoIntervalRequest\032-.m" - "avsdk.rpc.camera.StartPhotoIntervalRespo" - "nse\"\000\022p\n\021StopPhotoInterval\022+.mavsdk.rpc." - "camera.StopPhotoIntervalRequest\032,.mavsdk" - ".rpc.camera.StopPhotoIntervalResponse\"\000\022" - "[\n\nStartVideo\022$.mavsdk.rpc.camera.StartV" - "ideoRequest\032%.mavsdk.rpc.camera.StartVid" - "eoResponse\"\000\022X\n\tStopVideo\022#.mavsdk.rpc.c" - "amera.StopVideoRequest\032$.mavsdk.rpc.came" - "ra.StopVideoResponse\"\000\022z\n\023StartVideoStre" - "aming\022-.mavsdk.rpc.camera.StartVideoStre" - "amingRequest\032..mavsdk.rpc.camera.StartVi" - "deoStreamingResponse\"\004\200\265\030\001\022w\n\022StopVideoS" - "treaming\022,.mavsdk.rpc.camera.StopVideoSt" - "reamingRequest\032-.mavsdk.rpc.camera.StopV" - "ideoStreamingResponse\"\004\200\265\030\001\022R\n\007SetMode\022!" - ".mavsdk.rpc.camera.SetModeRequest\032\".mavs" - "dk.rpc.camera.SetModeResponse\"\000\022[\n\nListP" - "hotos\022$.mavsdk.rpc.camera.ListPhotosRequ" - "est\032%.mavsdk.rpc.camera.ListPhotosRespon" - "se\"\000\022]\n\rSubscribeMode\022\'.mavsdk.rpc.camer" - "a.SubscribeModeRequest\032\037.mavsdk.rpc.came" - "ra.ModeResponse\"\0000\001\022r\n\024SubscribeInformat" - "ion\022..mavsdk.rpc.camera.SubscribeInforma" - "tionRequest\032&.mavsdk.rpc.camera.Informat" - "ionResponse\"\0000\001\022~\n\030SubscribeVideoStreamI" - "nfo\0222.mavsdk.rpc.camera.SubscribeVideoSt" - "reamInfoRequest\032*.mavsdk.rpc.camera.Vide" - "oStreamInfoResponse\"\0000\001\022v\n\024SubscribeCapt" - "ureInfo\022..mavsdk.rpc.camera.SubscribeCap" - "tureInfoRequest\032&.mavsdk.rpc.camera.Capt" - "ureInfoResponse\"\004\200\265\030\0000\001\022c\n\017SubscribeStat" - "us\022).mavsdk.rpc.camera.SubscribeStatusRe" - "quest\032!.mavsdk.rpc.camera.StatusResponse" - "\"\0000\001\022\202\001\n\030SubscribeCurrentSettings\0222.mavs" - "dk.rpc.camera.SubscribeCurrentSettingsRe" - "quest\032*.mavsdk.rpc.camera.CurrentSetting" - "sResponse\"\004\200\265\030\0000\001\022\223\001\n\037SubscribePossibleS" - "ettingOptions\0229.mavsdk.rpc.camera.Subscr" - "ibePossibleSettingOptionsRequest\0321.mavsd" - "k.rpc.camera.PossibleSettingOptionsRespo" - "nse\"\0000\001\022[\n\nSetSetting\022$.mavsdk.rpc.camer" - "a.SetSettingRequest\032%.mavsdk.rpc.camera." - "SetSettingResponse\"\000\022[\n\nGetSetting\022$.mav" - "sdk.rpc.camera.GetSettingRequest\032%.mavsd" - "k.rpc.camera.GetSettingResponse\"\000\022d\n\rFor" - "matStorage\022\'.mavsdk.rpc.camera.FormatSto" - "rageRequest\032(.mavsdk.rpc.camera.FormatSt" - "orageResponse\"\000\022e\n\014SelectCamera\022&.mavsdk" - ".rpc.camera.SelectCameraRequest\032\'.mavsdk" - ".rpc.camera.SelectCameraResponse\"\004\200\265\030\001\022d" - "\n\rResetSettings\022\'.mavsdk.rpc.camera.Rese" - "tSettingsRequest\032(.mavsdk.rpc.camera.Res" - "etSettingsResponse\"\000B\037\n\020io.mavsdk.camera" - "B\013CameraProtob\006proto3" + "oRequest\"Y\n\027VideoStreamInfoResponse\022>\n\022v" + "ideo_stream_infos\030\001 \003(\0132\".mavsdk.rpc.cam" + "era.VideoStreamInfo\"\035\n\033SubscribeCaptureI" + "nfoRequest\"K\n\023CaptureInfoResponse\0224\n\014cap" + "ture_info\030\001 \001(\0132\036.mavsdk.rpc.camera.Capt" + "ureInfo\"\030\n\026SubscribeStatusRequest\"B\n\016Sta" + "tusResponse\0220\n\rcamera_status\030\001 \001(\0132\031.mav" + "sdk.rpc.camera.Status\"!\n\037SubscribeCurren" + "tSettingsRequest\"O\n\027CurrentSettingsRespo" + "nse\0224\n\020current_settings\030\001 \003(\0132\032.mavsdk.r" + "pc.camera.Setting\"(\n&SubscribePossibleSe" + "ttingOptionsRequest\"\\\n\036PossibleSettingOp" + "tionsResponse\022:\n\017setting_options\030\001 \003(\0132!" + ".mavsdk.rpc.camera.SettingOptions\"@\n\021Set" + "SettingRequest\022+\n\007setting\030\001 \001(\0132\032.mavsdk" + ".rpc.camera.Setting\"L\n\022SetSettingRespons" + "e\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.ca" + "mera.CameraResult\"@\n\021GetSettingRequest\022+" + "\n\007setting\030\001 \001(\0132\032.mavsdk.rpc.camera.Sett" + "ing\"y\n\022GetSettingResponse\0226\n\rcamera_resu" + "lt\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResul" + "t\022+\n\007setting\030\002 \001(\0132\032.mavsdk.rpc.camera.S" + "etting\"*\n\024FormatStorageRequest\022\022\n\nstorag" + "e_id\030\001 \001(\005\"O\n\025FormatStorageResponse\0226\n\rc" + "amera_result\030\001 \001(\0132\037.mavsdk.rpc.camera.C" + "ameraResult\"N\n\024SelectCameraResponse\0226\n\rc" + "amera_result\030\001 \001(\0132\037.mavsdk.rpc.camera.C" + "ameraResult\"(\n\023SelectCameraRequest\022\021\n\tca" + "mera_id\030\001 \001(\005\"\026\n\024ResetSettingsRequest\"O\n" + "\025ResetSettingsResponse\0226\n\rcamera_result\030" + "\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult\"\301" + "\002\n\014CameraResult\0226\n\006result\030\001 \001(\0162&.mavsdk" + ".rpc.camera.CameraResult.Result\022\022\n\nresul" + "t_str\030\002 \001(\t\"\344\001\n\006Result\022\022\n\016RESULT_UNKNOWN" + "\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROG" + "RESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED" + "\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006" + "\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO" + "_SYSTEM\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPPORTED" + "\020\t\"q\n\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\r" + "longitude_deg\030\002 \001(\001\022\033\n\023absolute_altitude" + "_m\030\003 \001(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n" + "\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003" + " \001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n\010roll_de" + "g\030\001 \001(\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007yaw_deg\030\003 " + "\001(\002\"\377\001\n\013CaptureInfo\022-\n\010position\030\001 \001(\0132\033." + "mavsdk.rpc.camera.Position\022:\n\023attitude_q" + "uaternion\030\002 \001(\0132\035.mavsdk.rpc.camera.Quat" + "ernion\022;\n\024attitude_euler_angle\030\003 \001(\0132\035.m" + "avsdk.rpc.camera.EulerAngle\022\023\n\013time_utc_" + "us\030\004 \001(\004\022\022\n\nis_success\030\005 \001(\010\022\r\n\005index\030\006 " + "\001(\005\022\020\n\010file_url\030\007 \001(\t\"\305\001\n\023VideoStreamSet" + "tings\022\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031horizont" + "al_resolution_pix\030\002 \001(\r\022\037\n\027vertical_reso" + "lution_pix\030\003 \001(\r\022\024\n\014bit_rate_b_s\030\004 \001(\r\022\024" + "\n\014rotation_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032\n\022hor" + "izontal_fov_deg\030\007 \001(\002\"\325\003\n\017VideoStreamInf" + "o\022\021\n\tstream_id\030\001 \001(\005\0228\n\010settings\030\002 \001(\0132&" + ".mavsdk.rpc.camera.VideoStreamSettings\022D" + "\n\006status\030\003 \001(\01624.mavsdk.rpc.camera.Video" + "StreamInfo.VideoStreamStatus\022H\n\010spectrum" + "\030\004 \001(\01626.mavsdk.rpc.camera.VideoStreamIn" + "fo.VideoStreamSpectrum\"]\n\021VideoStreamSta" + "tus\022#\n\037VIDEO_STREAM_STATUS_NOT_RUNNING\020\000" + "\022#\n\037VIDEO_STREAM_STATUS_IN_PROGRESS\020\001\"\205\001" + "\n\023VideoStreamSpectrum\022!\n\035VIDEO_STREAM_SP" + "ECTRUM_UNKNOWN\020\000\022\'\n#VIDEO_STREAM_SPECTRU" + "M_VISIBLE_LIGHT\020\001\022\"\n\036VIDEO_STREAM_SPECTR" + "UM_INFRARED\020\002\"\207\005\n\006Status\022\020\n\010video_on\030\001 \001" + "(\010\022\031\n\021photo_interval_on\030\002 \001(\010\022\030\n\020used_st" + "orage_mib\030\003 \001(\002\022\035\n\025available_storage_mib" + "\030\004 \001(\002\022\031\n\021total_storage_mib\030\005 \001(\002\022\030\n\020rec" + "ording_time_s\030\006 \001(\002\022\031\n\021media_folder_name" + "\030\007 \001(\t\022\?\n\016storage_status\030\010 \001(\0162\'.mavsdk." + "rpc.camera.Status.StorageStatus\022\022\n\nstora" + "ge_id\030\t \001(\r\022;\n\014storage_type\030\n \001(\0162%.mavs" + "dk.rpc.camera.Status.StorageType\"\221\001\n\rSto" + "rageStatus\022 \n\034STORAGE_STATUS_NOT_AVAILAB" + "LE\020\000\022\036\n\032STORAGE_STATUS_UNFORMATTED\020\001\022\034\n\030" + "STORAGE_STATUS_FORMATTED\020\002\022 \n\034STORAGE_ST" + "ATUS_NOT_SUPPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024" + "STORAGE_TYPE_UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_U" + "SB_STICK\020\001\022\023\n\017STORAGE_TYPE_SD\020\002\022\030\n\024STORA" + "GE_TYPE_MICROSD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027" + "\n\022STORAGE_TYPE_OTHER\020\376\001\"7\n\006Option\022\021\n\topt" + "ion_id\030\001 \001(\t\022\032\n\022option_description\030\002 \001(\t" + "\"w\n\007Setting\022\022\n\nsetting_id\030\001 \001(\t\022\033\n\023setti" + "ng_description\030\002 \001(\t\022)\n\006option\030\003 \001(\0132\031.m" + "avsdk.rpc.camera.Option\022\020\n\010is_range\030\004 \001(" + "\010\"\177\n\016SettingOptions\022\022\n\nsetting_id\030\001 \001(\t\022" + "\033\n\023setting_description\030\002 \001(\t\022*\n\007options\030" + "\003 \003(\0132\031.mavsdk.rpc.camera.Option\022\020\n\010is_r" + "ange\030\004 \001(\010\"\325\001\n\013Information\022\023\n\013vendor_nam" + "e\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\027\n\017focal_len" + "gth_mm\030\003 \001(\002\022!\n\031horizontal_sensor_size_m" + "m\030\004 \001(\002\022\037\n\027vertical_sensor_size_mm\030\005 \001(\002" + "\022 \n\030horizontal_resolution_px\030\006 \001(\r\022\036\n\026ve" + "rtical_resolution_px\030\007 \001(\r*8\n\004Mode\022\020\n\014MO" + "DE_UNKNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VID" + "EO\020\002*F\n\013PhotosRange\022\024\n\020PHOTOS_RANGE_ALL\020" + "\000\022!\n\035PHOTOS_RANGE_SINCE_CONNECTION\020\0012\271\022\n" + "\rCameraService\022R\n\007Prepare\022!.mavsdk.rpc.c" + "amera.PrepareRequest\032\".mavsdk.rpc.camera" + ".PrepareResponse\"\000\022X\n\tTakePhoto\022#.mavsdk" + ".rpc.camera.TakePhotoRequest\032$.mavsdk.rp" + "c.camera.TakePhotoResponse\"\000\022s\n\022StartPho" + "toInterval\022,.mavsdk.rpc.camera.StartPhot" + "oIntervalRequest\032-.mavsdk.rpc.camera.Sta" + "rtPhotoIntervalResponse\"\000\022p\n\021StopPhotoIn" + "terval\022+.mavsdk.rpc.camera.StopPhotoInte" + "rvalRequest\032,.mavsdk.rpc.camera.StopPhot" + "oIntervalResponse\"\000\022[\n\nStartVideo\022$.mavs" + "dk.rpc.camera.StartVideoRequest\032%.mavsdk" + ".rpc.camera.StartVideoResponse\"\000\022X\n\tStop" + "Video\022#.mavsdk.rpc.camera.StopVideoReque" + "st\032$.mavsdk.rpc.camera.StopVideoResponse" + "\"\000\022z\n\023StartVideoStreaming\022-.mavsdk.rpc.c" + "amera.StartVideoStreamingRequest\032..mavsd" + "k.rpc.camera.StartVideoStreamingResponse" + "\"\004\200\265\030\001\022w\n\022StopVideoStreaming\022,.mavsdk.rp" + "c.camera.StopVideoStreamingRequest\032-.mav" + "sdk.rpc.camera.StopVideoStreamingRespons" + "e\"\004\200\265\030\001\022R\n\007SetMode\022!.mavsdk.rpc.camera.S" + "etModeRequest\032\".mavsdk.rpc.camera.SetMod" + "eResponse\"\000\022[\n\nListPhotos\022$.mavsdk.rpc.c" + "amera.ListPhotosRequest\032%.mavsdk.rpc.cam" + "era.ListPhotosResponse\"\000\022]\n\rSubscribeMod" + "e\022\'.mavsdk.rpc.camera.SubscribeModeReque" + "st\032\037.mavsdk.rpc.camera.ModeResponse\"\0000\001\022" + "r\n\024SubscribeInformation\022..mavsdk.rpc.cam" + "era.SubscribeInformationRequest\032&.mavsdk" + ".rpc.camera.InformationResponse\"\0000\001\022~\n\030S" + "ubscribeVideoStreamInfo\0222.mavsdk.rpc.cam" + "era.SubscribeVideoStreamInfoRequest\032*.ma" + "vsdk.rpc.camera.VideoStreamInfoResponse\"" + "\0000\001\022v\n\024SubscribeCaptureInfo\022..mavsdk.rpc" + ".camera.SubscribeCaptureInfoRequest\032&.ma" + "vsdk.rpc.camera.CaptureInfoResponse\"\004\200\265\030" + "\0000\001\022c\n\017SubscribeStatus\022).mavsdk.rpc.came" + "ra.SubscribeStatusRequest\032!.mavsdk.rpc.c" + "amera.StatusResponse\"\0000\001\022\202\001\n\030SubscribeCu" + "rrentSettings\0222.mavsdk.rpc.camera.Subscr" + "ibeCurrentSettingsRequest\032*.mavsdk.rpc.c" + "amera.CurrentSettingsResponse\"\004\200\265\030\0000\001\022\223\001" + "\n\037SubscribePossibleSettingOptions\0229.mavs" + "dk.rpc.camera.SubscribePossibleSettingOp" + "tionsRequest\0321.mavsdk.rpc.camera.Possibl" + "eSettingOptionsResponse\"\0000\001\022[\n\nSetSettin" + "g\022$.mavsdk.rpc.camera.SetSettingRequest\032" + "%.mavsdk.rpc.camera.SetSettingResponse\"\000" + "\022[\n\nGetSetting\022$.mavsdk.rpc.camera.GetSe" + "ttingRequest\032%.mavsdk.rpc.camera.GetSett" + "ingResponse\"\000\022d\n\rFormatStorage\022\'.mavsdk." + "rpc.camera.FormatStorageRequest\032(.mavsdk" + ".rpc.camera.FormatStorageResponse\"\000\022e\n\014S" + "electCamera\022&.mavsdk.rpc.camera.SelectCa" + "meraRequest\032\'.mavsdk.rpc.camera.SelectCa" + "meraResponse\"\004\200\265\030\001\022d\n\rResetSettings\022\'.ma" + "vsdk.rpc.camera.ResetSettingsRequest\032(.m" + "avsdk.rpc.camera.ResetSettingsResponse\"\000" + "B\037\n\020io.mavsdk.cameraB\013CameraProtob\006proto" + "3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_2fcamera_2eproto_deps[1] = { @@ -1980,7 +1983,7 @@ static ::absl::once_flag descriptor_table_camera_2fcamera_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_camera_2fcamera_2eproto = { false, false, - 7941, + 7961, descriptor_table_protodef_camera_2fcamera_2eproto, "camera/camera.proto", &descriptor_table_camera_2fcamera_2eproto_once, @@ -5770,18 +5773,8 @@ ::google::protobuf::Metadata SubscribeVideoStreamInfoRequest::GetMetadata() cons class VideoStreamInfoResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(VideoStreamInfoResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::VideoStreamInfo& video_stream_info(const VideoStreamInfoResponse* msg); - static void set_has_video_stream_info(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera::VideoStreamInfo& VideoStreamInfoResponse::_Internal::video_stream_info(const VideoStreamInfoResponse* msg) { - return *msg->_impl_.video_stream_info_; -} VideoStreamInfoResponse::VideoStreamInfoResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); @@ -5790,7 +5783,7 @@ VideoStreamInfoResponse::VideoStreamInfoResponse(::google::protobuf::Arena* aren inline PROTOBUF_NDEBUG_INLINE VideoStreamInfoResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) - : _has_bits_{from._has_bits_}, + : video_stream_infos_{visibility, arena, from.video_stream_infos_}, _cached_size_{0} {} VideoStreamInfoResponse::VideoStreamInfoResponse( @@ -5802,21 +5795,17 @@ VideoStreamInfoResponse::VideoStreamInfoResponse( _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.video_stream_info_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::VideoStreamInfo>(arena, *from._impl_.video_stream_info_) - : nullptr; // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.VideoStreamInfoResponse) } inline PROTOBUF_NDEBUG_INLINE VideoStreamInfoResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : _cached_size_{0} {} + : video_stream_infos_{visibility, arena}, + _cached_size_{0} {} inline void VideoStreamInfoResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.video_stream_info_ = {}; } VideoStreamInfoResponse::~VideoStreamInfoResponse() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.VideoStreamInfoResponse) @@ -5825,7 +5814,6 @@ VideoStreamInfoResponse::~VideoStreamInfoResponse() { } inline void VideoStreamInfoResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.video_stream_info_; _impl_.~Impl_(); } @@ -5836,12 +5824,7 @@ PROTOBUF_NOINLINE void VideoStreamInfoResponse::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.video_stream_info_ != nullptr); - _impl_.video_stream_info_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.video_stream_infos_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -5855,7 +5838,7 @@ const char* VideoStreamInfoResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 const ::_pbi::TcParseTable<0, 1, 1, 0, 2> VideoStreamInfoResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(VideoStreamInfoResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -5867,15 +5850,15 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> VideoStreamInfoResponse::_table_ = { &_VideoStreamInfoResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfoResponse, _impl_.video_stream_info_)}}, + // repeated .mavsdk.rpc.camera.VideoStreamInfo video_stream_infos = 1; + {::_pbi::TcParser::FastMtR1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfoResponse, _impl_.video_stream_infos_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; - {PROTOBUF_FIELD_OFFSET(VideoStreamInfoResponse, _impl_.video_stream_info_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // repeated .mavsdk.rpc.camera.VideoStreamInfo video_stream_infos = 1; + {PROTOBUF_FIELD_OFFSET(VideoStreamInfoResponse, _impl_.video_stream_infos_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::VideoStreamInfo>()}, }}, {{ @@ -5889,12 +5872,12 @@ ::uint8_t* VideoStreamInfoResponse::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::video_stream_info(this), - _Internal::video_stream_info(this).GetCachedSize(), target, stream); + // repeated .mavsdk.rpc.camera.VideoStreamInfo video_stream_infos = 1; + for (unsigned i = 0, + n = static_cast(this->_internal_video_stream_infos_size()); i < n; i++) { + const auto& repfield = this->_internal_video_stream_infos().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(1, repfield, repfield.GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -5914,13 +5897,12 @@ ::size_t VideoStreamInfoResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { + // repeated .mavsdk.rpc.camera.VideoStreamInfo video_stream_infos = 1; + total_size += 1UL * this->_internal_video_stream_infos_size(); + for (const auto& msg : this->_internal_video_stream_infos()) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.video_stream_info_); + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); } - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } @@ -5940,10 +5922,8 @@ void VideoStreamInfoResponse::MergeImpl(::google::protobuf::Message& to_msg, con ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_video_stream_info()->::mavsdk::rpc::camera::VideoStreamInfo::MergeFrom( - from._internal_video_stream_info()); - } + _this->_internal_mutable_video_stream_infos()->MergeFrom( + from._internal_video_stream_infos()); _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } @@ -5964,8 +5944,7 @@ ::_pbi::CachedSize* VideoStreamInfoResponse::AccessCachedSize() const { void VideoStreamInfoResponse::InternalSwap(VideoStreamInfoResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.video_stream_info_, other->_impl_.video_stream_info_); + _impl_.video_stream_infos_.InternalSwap(&other->_impl_.video_stream_infos_); } ::google::protobuf::Metadata VideoStreamInfoResponse::GetMetadata() const { @@ -10691,11 +10670,11 @@ VideoStreamInfo::VideoStreamInfo( ? CreateMaybeMessage<::mavsdk::rpc::camera::VideoStreamSettings>(arena, *from._impl_.settings_) : nullptr; ::memcpy(reinterpret_cast(&_impl_) + - offsetof(Impl_, status_), + offsetof(Impl_, stream_id_), reinterpret_cast(&from._impl_) + - offsetof(Impl_, status_), + offsetof(Impl_, stream_id_), offsetof(Impl_, spectrum_) - - offsetof(Impl_, status_) + + offsetof(Impl_, stream_id_) + sizeof(Impl_::spectrum_)); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.VideoStreamInfo) @@ -10737,9 +10716,9 @@ PROTOBUF_NOINLINE void VideoStreamInfo::Clear() { ABSL_DCHECK(_impl_.settings_ != nullptr); _impl_.settings_->Clear(); } - ::memset(&_impl_.status_, 0, static_cast<::size_t>( + ::memset(&_impl_.stream_id_, 0, static_cast<::size_t>( reinterpret_cast(&_impl_.spectrum_) - - reinterpret_cast(&_impl_.status_)) + sizeof(_impl_.spectrum_)); + reinterpret_cast(&_impl_.stream_id_)) + sizeof(_impl_.spectrum_)); _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -10752,40 +10731,45 @@ const char* VideoStreamInfo::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 3, 1, 0, 2> VideoStreamInfo::_table_ = { +const ::_pbi::TcParseTable<2, 4, 1, 0, 2> VideoStreamInfo::_table_ = { { PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_._has_bits_), 0, // no _extensions_ - 3, 24, // max_field_number, fast_idx_mask + 4, 24, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967288, // skipmap + 4294967280, // skipmap offsetof(decltype(_table_), field_entries), - 3, // num_field_entries + 4, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), &_VideoStreamInfo_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - {::_pbi::TcParser::MiniParse, {}}, - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.spectrum_), 63>(), + {32, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_)}}, + // int32 stream_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.stream_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.stream_id_)}}, + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_)}}, - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + {18, 0, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_)}}, + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.status_), 63>(), - {16, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.status_)}}, - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.spectrum_), 63>(), - {24, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_)}}, + {24, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.status_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // int32 stream_id = 1; + {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.stream_id_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.status_), -1, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_), -1, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, {{ @@ -10801,26 +10785,33 @@ ::uint8_t* VideoStreamInfo::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_stream_id(), target); + } + cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::settings(this), + 2, _Internal::settings(this), _Internal::settings(this).GetCachedSize(), target, stream); } - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; if (this->_internal_status() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 2, this->_internal_status(), target); + 3, this->_internal_status(), target); } - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; if (this->_internal_spectrum() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 3, this->_internal_spectrum(), target); + 4, this->_internal_spectrum(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -10840,20 +10831,26 @@ ::size_t VideoStreamInfo::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.settings_); } - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; if (this->_internal_status() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_status()); } - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; if (this->_internal_spectrum() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_spectrum()); @@ -10882,6 +10879,9 @@ void VideoStreamInfo::MergeImpl(::google::protobuf::Message& to_msg, const ::goo _this->_internal_mutable_settings()->::mavsdk::rpc::camera::VideoStreamSettings::MergeFrom( from._internal_settings()); } + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } if (from._internal_status() != 0) { _this->_internal_set_status(from._internal_status()); } diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.h b/src/mavsdk_server/src/generated/camera/camera.pb.h index eabc9a72cc..e13e438328 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.pb.h @@ -5716,11 +5716,12 @@ class VideoStreamInfo final : // accessors ------------------------------------------------------- enum : int { - kSettingsFieldNumber = 1, - kStatusFieldNumber = 2, - kSpectrumFieldNumber = 3, + kSettingsFieldNumber = 2, + kStreamIdFieldNumber = 1, + kStatusFieldNumber = 3, + kSpectrumFieldNumber = 4, }; - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; bool has_settings() const; void clear_settings() ; const ::mavsdk::rpc::camera::VideoStreamSettings& settings() const; @@ -5735,7 +5736,17 @@ class VideoStreamInfo final : ::mavsdk::rpc::camera::VideoStreamSettings* _internal_mutable_settings(); public: - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; void clear_status() ; ::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamStatus status() const; void set_status(::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamStatus value); @@ -5745,7 +5756,7 @@ class VideoStreamInfo final : void _internal_set_status(::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamStatus value); public: - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; void clear_spectrum() ; ::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamSpectrum spectrum() const; void set_spectrum(::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamSpectrum value); @@ -5761,7 +5772,7 @@ class VideoStreamInfo final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 1, + 2, 4, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -5781,6 +5792,7 @@ class VideoStreamInfo final : ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::camera::VideoStreamSettings* settings_; + ::int32_t stream_id_; int status_; int spectrum_; PROTOBUF_TSAN_DECLARE_MEMBER @@ -9365,23 +9377,26 @@ class VideoStreamInfoResponse final : // accessors ------------------------------------------------------- enum : int { - kVideoStreamInfoFieldNumber = 1, + kVideoStreamInfosFieldNumber = 1, }; - // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; - bool has_video_stream_info() const; - void clear_video_stream_info() ; - const ::mavsdk::rpc::camera::VideoStreamInfo& video_stream_info() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera::VideoStreamInfo* release_video_stream_info(); - ::mavsdk::rpc::camera::VideoStreamInfo* mutable_video_stream_info(); - void set_allocated_video_stream_info(::mavsdk::rpc::camera::VideoStreamInfo* value); - void unsafe_arena_set_allocated_video_stream_info(::mavsdk::rpc::camera::VideoStreamInfo* value); - ::mavsdk::rpc::camera::VideoStreamInfo* unsafe_arena_release_video_stream_info(); - + // repeated .mavsdk.rpc.camera.VideoStreamInfo video_stream_infos = 1; + int video_stream_infos_size() const; private: - const ::mavsdk::rpc::camera::VideoStreamInfo& _internal_video_stream_info() const; - ::mavsdk::rpc::camera::VideoStreamInfo* _internal_mutable_video_stream_info(); + int _internal_video_stream_infos_size() const; public: + void clear_video_stream_infos() ; + ::mavsdk::rpc::camera::VideoStreamInfo* mutable_video_stream_infos(int index); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::camera::VideoStreamInfo >* + mutable_video_stream_infos(); + private: + const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera::VideoStreamInfo>& _internal_video_stream_infos() const; + ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera::VideoStreamInfo>* _internal_mutable_video_stream_infos(); + public: + const ::mavsdk::rpc::camera::VideoStreamInfo& video_stream_infos(int index) const; + ::mavsdk::rpc::camera::VideoStreamInfo* add_video_stream_infos(); + const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::camera::VideoStreamInfo >& + video_stream_infos() const; // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.VideoStreamInfoResponse) private: class _Internal; @@ -9405,9 +9420,8 @@ class VideoStreamInfoResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::camera::VideoStreamInfo > video_stream_infos_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera::VideoStreamInfo* video_stream_info_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -12081,100 +12095,53 @@ inline void ModeResponse::_internal_set_mode(::mavsdk::rpc::camera::Mode value) // VideoStreamInfoResponse -// .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; -inline bool VideoStreamInfoResponse::has_video_stream_info() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.video_stream_info_ != nullptr); - return value; +// repeated .mavsdk.rpc.camera.VideoStreamInfo video_stream_infos = 1; +inline int VideoStreamInfoResponse::_internal_video_stream_infos_size() const { + return _internal_video_stream_infos().size(); } -inline void VideoStreamInfoResponse::clear_video_stream_info() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.video_stream_info_ != nullptr) _impl_.video_stream_info_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; +inline int VideoStreamInfoResponse::video_stream_infos_size() const { + return _internal_video_stream_infos_size(); } -inline const ::mavsdk::rpc::camera::VideoStreamInfo& VideoStreamInfoResponse::_internal_video_stream_info() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::camera::VideoStreamInfo* p = _impl_.video_stream_info_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera::_VideoStreamInfo_default_instance_); +inline void VideoStreamInfoResponse::clear_video_stream_infos() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.video_stream_infos_.Clear(); } -inline const ::mavsdk::rpc::camera::VideoStreamInfo& VideoStreamInfoResponse::video_stream_info() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_info) - return _internal_video_stream_info(); +inline ::mavsdk::rpc::camera::VideoStreamInfo* VideoStreamInfoResponse::mutable_video_stream_infos(int index) + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_infos) + return _internal_mutable_video_stream_infos()->Mutable(index); } -inline void VideoStreamInfoResponse::unsafe_arena_set_allocated_video_stream_info(::mavsdk::rpc::camera::VideoStreamInfo* value) { +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera::VideoStreamInfo>* VideoStreamInfoResponse::mutable_video_stream_infos() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_infos) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.video_stream_info_); - } - _impl_.video_stream_info_ = reinterpret_cast<::mavsdk::rpc::camera::VideoStreamInfo*>(value); - if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_info) + return _internal_mutable_video_stream_infos(); } -inline ::mavsdk::rpc::camera::VideoStreamInfo* VideoStreamInfoResponse::release_video_stream_info() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera::VideoStreamInfo* released = _impl_.video_stream_info_; - _impl_.video_stream_info_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - if (GetArena() == nullptr) { - delete old; - } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArena() != nullptr) { - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return released; +inline const ::mavsdk::rpc::camera::VideoStreamInfo& VideoStreamInfoResponse::video_stream_infos(int index) const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_infos) + return _internal_video_stream_infos().Get(index); } -inline ::mavsdk::rpc::camera::VideoStreamInfo* VideoStreamInfoResponse::unsafe_arena_release_video_stream_info() { +inline ::mavsdk::rpc::camera::VideoStreamInfo* VideoStreamInfoResponse::add_video_stream_infos() ABSL_ATTRIBUTE_LIFETIME_BOUND { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_info) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera::VideoStreamInfo* temp = _impl_.video_stream_info_; - _impl_.video_stream_info_ = nullptr; - return temp; + ::mavsdk::rpc::camera::VideoStreamInfo* _add = _internal_mutable_video_stream_infos()->Add(); + // @@protoc_insertion_point(field_add:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_infos) + return _add; } -inline ::mavsdk::rpc::camera::VideoStreamInfo* VideoStreamInfoResponse::_internal_mutable_video_stream_info() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.video_stream_info_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera::VideoStreamInfo>(GetArena()); - _impl_.video_stream_info_ = reinterpret_cast<::mavsdk::rpc::camera::VideoStreamInfo*>(p); - } - return _impl_.video_stream_info_; +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera::VideoStreamInfo>& VideoStreamInfoResponse::video_stream_infos() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_infos) + return _internal_video_stream_infos(); } -inline ::mavsdk::rpc::camera::VideoStreamInfo* VideoStreamInfoResponse::mutable_video_stream_info() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::camera::VideoStreamInfo* _msg = _internal_mutable_video_stream_info(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_info) - return _msg; +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera::VideoStreamInfo>& +VideoStreamInfoResponse::_internal_video_stream_infos() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.video_stream_infos_; } -inline void VideoStreamInfoResponse::set_allocated_video_stream_info(::mavsdk::rpc::camera::VideoStreamInfo* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::camera::VideoStreamInfo*>(_impl_.video_stream_info_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera::VideoStreamInfo*>(value)->GetArena(); - if (message_arena != submessage_arena) { - value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); - } - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - - _impl_.video_stream_info_ = reinterpret_cast<::mavsdk::rpc::camera::VideoStreamInfo*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera.VideoStreamInfoResponse.video_stream_info) +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera::VideoStreamInfo>* +VideoStreamInfoResponse::_internal_mutable_video_stream_infos() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.video_stream_infos_; } // ------------------------------------------------------------------- @@ -14311,7 +14278,30 @@ inline void VideoStreamSettings::_internal_set_horizontal_fov_deg(float value) { // VideoStreamInfo -// .mavsdk.rpc.camera.VideoStreamSettings settings = 1; +// int32 stream_id = 1; +inline void VideoStreamInfo::clear_stream_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.stream_id_ = 0; +} +inline ::int32_t VideoStreamInfo::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.VideoStreamInfo.stream_id) + return _internal_stream_id(); +} +inline void VideoStreamInfo::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.VideoStreamInfo.stream_id) +} +inline ::int32_t VideoStreamInfo::_internal_stream_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.stream_id_; +} +inline void VideoStreamInfo::_internal_set_stream_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.stream_id_ = value; +} + +// .mavsdk.rpc.camera.VideoStreamSettings settings = 2; inline bool VideoStreamInfo::has_settings() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; PROTOBUF_ASSUME(!value || _impl_.settings_ != nullptr); @@ -14407,7 +14397,7 @@ inline void VideoStreamInfo::set_allocated_settings(::mavsdk::rpc::camera::Video // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera.VideoStreamInfo.settings) } -// .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; +// .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; inline void VideoStreamInfo::clear_status() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.status_ = 0; @@ -14430,7 +14420,7 @@ inline void VideoStreamInfo::_internal_set_status(::mavsdk::rpc::camera::VideoSt _impl_.status_ = value; } -// .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; +// .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; inline void VideoStreamInfo::clear_spectrum() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.spectrum_ = 0; diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index ecbb047d4b..6ff8639689 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -25,7 +25,7 @@ namespace camera_server { static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/SetInformation", - "/mavsdk.rpc.camera_server.CameraServerService/SetVideoStreaming", + "/mavsdk.rpc.camera_server.CameraServerService/SetVideoStreamInfo", "/mavsdk.rpc.camera_server.CameraServerService/SetInProgress", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", @@ -57,7 +57,7 @@ std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const s CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) : channel_(channel), rpcmethod_SetInformation_(CameraServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetVideoStreaming_(CameraServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetVideoStreamInfo_(CameraServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SetInProgress_(CameraServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeTakePhoto_(CameraServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_RespondTakePhoto_(CameraServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) @@ -104,25 +104,25 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationR return result; } -::grpc::Status CameraServerService::Stub::SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetVideoStreaming_, context, request, response); +::grpc::Status CameraServerService::Stub::SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetVideoStreamInfo_, context, request, response); } -void CameraServerService::Stub::async::SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetVideoStreaming_, context, request, response, std::move(f)); +void CameraServerService::Stub::async::SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetVideoStreamInfo_, context, request, response, std::move(f)); } -void CameraServerService::Stub::async::SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetVideoStreaming_, context, request, response, reactor); +void CameraServerService::Stub::async::SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetVideoStreamInfo_, context, request, response, reactor); } -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* CameraServerService::Stub::PrepareAsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse, ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetVideoStreaming_, context, request); +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* CameraServerService::Stub::PrepareAsyncSetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse, ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetVideoStreamInfo_, context, request); } -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* CameraServerService::Stub::AsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* CameraServerService::Stub::AsyncSetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { auto* result = - this->PrepareAsyncSetVideoStreamingRaw(context, request, cq); + this->PrepareAsyncSetVideoStreamInfoRaw(context, request, cq); result->StartCall(); return result; } @@ -554,12 +554,12 @@ CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[1], ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* req, - ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* resp) { - return service->SetVideoStreaming(ctx, req, resp); + const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* req, + ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* resp) { + return service->SetVideoStreamInfo(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[2], @@ -783,7 +783,7 @@ ::grpc::Status CameraServerService::Service::SetInformation(::grpc::ServerContex return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraServerService::Service::SetVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) { +::grpc::Status CameraServerService::Service::SetVideoStreamInfo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response) { (void) context; (void) request; (void) response; diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index df7b4635f3..823c25f12e 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -46,13 +46,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>> PrepareAsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>>(PrepareAsyncSetInformationRaw(context, request, cq)); } - // Sets video streaming settings. - virtual ::grpc::Status SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>> AsyncSetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>>(AsyncSetVideoStreamingRaw(context, request, cq)); + // Sets video stream info. + virtual ::grpc::Status SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>> AsyncSetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>>(AsyncSetVideoStreamInfoRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>> PrepareAsyncSetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>>(PrepareAsyncSetVideoStreamingRaw(context, request, cq)); + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>> PrepareAsyncSetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>>(PrepareAsyncSetVideoStreamInfoRaw(context, request, cq)); } // 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. virtual ::grpc::Status SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) = 0; @@ -248,9 +248,9 @@ class CameraServerService final { // Sets the camera information. This must be called as soon as the camera server is created. virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function) = 0; virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Sets video streaming settings. - virtual void SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, std::function) = 0; - virtual void SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Sets video stream info. + virtual void SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response, std::function) = 0; + virtual void SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // 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. virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) = 0; virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; @@ -311,8 +311,8 @@ class CameraServerService final { private: virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>* AsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>* PrepareAsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* AsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* PrepareAsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* AsyncSetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* PrepareAsyncSetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>* AsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>* PrepareAsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) = 0; @@ -376,12 +376,12 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>> PrepareAsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>>(PrepareAsyncSetInformationRaw(context, request, cq)); } - ::grpc::Status SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>> AsyncSetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>>(AsyncSetVideoStreamingRaw(context, request, cq)); + ::grpc::Status SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>> AsyncSetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>>(AsyncSetVideoStreamInfoRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>> PrepareAsyncSetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>>(PrepareAsyncSetVideoStreamingRaw(context, request, cq)); + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>> PrepareAsyncSetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>>(PrepareAsyncSetVideoStreamInfoRaw(context, request, cq)); } ::grpc::Status SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>> AsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { @@ -555,8 +555,8 @@ class CameraServerService final { public: void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function) override; void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) override; - void SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, std::function) override; - void SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response, std::function) override; + void SetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) override; void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) override; @@ -602,8 +602,8 @@ class CameraServerService final { class async async_stub_{this}; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>* AsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>* PrepareAsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* AsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* PrepareAsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* AsyncSetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* PrepareAsyncSetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>* AsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>* PrepareAsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) override; @@ -657,7 +657,7 @@ class CameraServerService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* AsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* PrepareAsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; - const ::grpc::internal::RpcMethod rpcmethod_SetVideoStreaming_; + const ::grpc::internal::RpcMethod rpcmethod_SetVideoStreamInfo_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_RespondTakePhoto_; @@ -688,8 +688,8 @@ class CameraServerService final { virtual ~Service(); // Sets the camera information. This must be called as soon as the camera server is created. virtual ::grpc::Status SetInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response); - // Sets video streaming settings. - virtual ::grpc::Status SetVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response); + // Sets video stream info. + virtual ::grpc::Status SetVideoStreamInfo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response); // 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. virtual ::grpc::Status SetInProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response); // Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. @@ -754,22 +754,22 @@ class CameraServerService final { } }; template - class WithAsyncMethod_SetVideoStreaming : public BaseClass { + class WithAsyncMethod_SetVideoStreamInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithAsyncMethod_SetVideoStreaming() { + WithAsyncMethod_SetVideoStreamInfo() { ::grpc::Service::MarkMethodAsync(1); } - ~WithAsyncMethod_SetVideoStreaming() override { + ~WithAsyncMethod_SetVideoStreamInfo() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + ::grpc::Status SetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestSetVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + void RequestSetVideoStreamInfo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); } }; @@ -1193,7 +1193,7 @@ class CameraServerService final { ::grpc::Service::RequestAsyncUnary(22, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > AsyncService; + typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -1222,31 +1222,31 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) { return nullptr; } }; template - class WithCallbackMethod_SetVideoStreaming : public BaseClass { + class WithCallbackMethod_SetVideoStreamInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithCallbackMethod_SetVideoStreaming() { + WithCallbackMethod_SetVideoStreamInfo() { ::grpc::Service::MarkMethodCallback(1, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>( + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>( [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) { return this->SetVideoStreaming(context, request, response); }));} - void SetMessageAllocatorFor_SetVideoStreaming( - ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* allocator) { + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* response) { return this->SetVideoStreamInfo(context, request, response); }));} + void SetMessageAllocatorFor_SetVideoStreamInfo( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* allocator) { ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>*>(handler) + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>*>(handler) ->SetMessageAllocator(allocator); } - ~WithCallbackMethod_SetVideoStreaming() override { + ~WithCallbackMethod_SetVideoStreamInfo() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + ::grpc::Status SetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* SetVideoStreaming( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) { return nullptr; } + virtual ::grpc::ServerUnaryReactor* SetVideoStreamInfo( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* /*response*/) { return nullptr; } }; template class WithCallbackMethod_SetInProgress : public BaseClass { @@ -1765,7 +1765,7 @@ class CameraServerService final { virtual ::grpc::ServerUnaryReactor* RespondResetSettings( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > CallbackService; + typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -1785,18 +1785,18 @@ class CameraServerService final { } }; template - class WithGenericMethod_SetVideoStreaming : public BaseClass { + class WithGenericMethod_SetVideoStreamInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SetVideoStreaming() { + WithGenericMethod_SetVideoStreamInfo() { ::grpc::Service::MarkMethodGeneric(1); } - ~WithGenericMethod_SetVideoStreaming() override { + ~WithGenericMethod_SetVideoStreamInfo() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + ::grpc::Status SetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } @@ -2179,22 +2179,22 @@ class CameraServerService final { } }; template - class WithRawMethod_SetVideoStreaming : public BaseClass { + class WithRawMethod_SetVideoStreamInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SetVideoStreaming() { + WithRawMethod_SetVideoStreamInfo() { ::grpc::Service::MarkMethodRaw(1); } - ~WithRawMethod_SetVideoStreaming() override { + ~WithRawMethod_SetVideoStreamInfo() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + ::grpc::Status SetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestSetVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + void RequestSetVideoStreamInfo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); } }; @@ -2641,25 +2641,25 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SetVideoStreaming : public BaseClass { + class WithRawCallbackMethod_SetVideoStreamInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_SetVideoStreaming() { + WithRawCallbackMethod_SetVideoStreamInfo() { ::grpc::Service::MarkMethodRawCallback(1, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetVideoStreaming(context, request, response); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetVideoStreamInfo(context, request, response); })); } - ~WithRawCallbackMethod_SetVideoStreaming() override { + ~WithRawCallbackMethod_SetVideoStreamInfo() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + ::grpc::Status SetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* SetVideoStreaming( + virtual ::grpc::ServerUnaryReactor* SetVideoStreamInfo( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template @@ -3152,31 +3152,31 @@ class CameraServerService final { virtual ::grpc::Status StreamedSetInformation(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::SetInformationRequest,::mavsdk::rpc::camera_server::SetInformationResponse>* server_unary_streamer) = 0; }; template - class WithStreamedUnaryMethod_SetVideoStreaming : public BaseClass { + class WithStreamedUnaryMethod_SetVideoStreamInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithStreamedUnaryMethod_SetVideoStreaming() { + WithStreamedUnaryMethod_SetVideoStreamInfo() { ::grpc::Service::MarkMethodStreamed(1, new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>( + ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>( [this](::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* streamer) { - return this->StreamedSetVideoStreaming(context, + ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* streamer) { + return this->StreamedSetVideoStreamInfo(context, streamer); })); } - ~WithStreamedUnaryMethod_SetVideoStreaming() override { + ~WithStreamedUnaryMethod_SetVideoStreamInfo() override { BaseClassMustBeDerivedFromService(this); } // disable regular version of this method - ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + ::grpc::Status SetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } // replace default version of method with streamed unary - virtual ::grpc::Status StreamedSetVideoStreaming(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest,::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* server_unary_streamer) = 0; + virtual ::grpc::Status StreamedSetVideoStreamInfo(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest,::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse>* server_unary_streamer) = 0; }; template class WithStreamedUnaryMethod_SetInProgress : public BaseClass { @@ -3475,7 +3475,7 @@ class CameraServerService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedRespondResetSettings(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest,::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > StreamedUnaryService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeTakePhoto : public BaseClass { private: @@ -3747,7 +3747,7 @@ class CameraServerService final { virtual ::grpc::Status StreamedSubscribeResetSettings(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest,::mavsdk::rpc::camera_server::ResetSettingsResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > > > > > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > StreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index d24e8e5734..59bda93a26 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -24,27 +24,32 @@ namespace mavsdk { namespace rpc { namespace camera_server { -inline constexpr VideoStreaming::Impl_::Impl_( +inline constexpr VideoStreamSettings::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : rtsp_uri_( + : uri_( &::google::protobuf::internal::fixed_address_empty_string, ::_pbi::ConstantInitialized()), - has_rtsp_server_{false}, + frame_rate_hz_{0}, + horizontal_resolution_pix_{0u}, + vertical_resolution_pix_{0u}, + bit_rate_b_s_{0u}, + rotation_deg_{0u}, + horizontal_fov_deg_{0}, _cached_size_{0} {} template -PROTOBUF_CONSTEXPR VideoStreaming::VideoStreaming(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR VideoStreamSettings::VideoStreamSettings(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct VideoStreamingDefaultTypeInternal { - PROTOBUF_CONSTEXPR VideoStreamingDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~VideoStreamingDefaultTypeInternal() {} +struct VideoStreamSettingsDefaultTypeInternal { + PROTOBUF_CONSTEXPR VideoStreamSettingsDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~VideoStreamSettingsDefaultTypeInternal() {} union { - VideoStreaming _instance; + VideoStreamSettings _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 VideoStreamingDefaultTypeInternal _VideoStreaming_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 VideoStreamSettingsDefaultTypeInternal _VideoStreamSettings_default_instance_; inline constexpr TakePhotoResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept @@ -661,43 +666,46 @@ struct CameraServerResultDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CameraServerResultDefaultTypeInternal _CameraServerResult_default_instance_; -inline constexpr SetVideoStreamingResponse::Impl_::Impl_( +inline constexpr VideoStreamInfo::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, - camera_server_result_{nullptr} {} + settings_{nullptr}, + stream_id_{0}, + status_{static_cast< ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus >(0)}, + spectrum_{static_cast< ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum >(0)} {} template -PROTOBUF_CONSTEXPR SetVideoStreamingResponse::SetVideoStreamingResponse(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR VideoStreamInfo::VideoStreamInfo(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct SetVideoStreamingResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR SetVideoStreamingResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SetVideoStreamingResponseDefaultTypeInternal() {} +struct VideoStreamInfoDefaultTypeInternal { + PROTOBUF_CONSTEXPR VideoStreamInfoDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~VideoStreamInfoDefaultTypeInternal() {} union { - SetVideoStreamingResponse _instance; + VideoStreamInfo _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetVideoStreamingResponseDefaultTypeInternal _SetVideoStreamingResponse_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 VideoStreamInfoDefaultTypeInternal _VideoStreamInfo_default_instance_; -inline constexpr SetVideoStreamingRequest::Impl_::Impl_( +inline constexpr SetVideoStreamInfoResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, - video_streaming_{nullptr} {} + camera_server_result_{nullptr} {} template -PROTOBUF_CONSTEXPR SetVideoStreamingRequest::SetVideoStreamingRequest(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR SetVideoStreamInfoResponse::SetVideoStreamInfoResponse(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct SetVideoStreamingRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SetVideoStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SetVideoStreamingRequestDefaultTypeInternal() {} +struct SetVideoStreamInfoResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetVideoStreamInfoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetVideoStreamInfoResponseDefaultTypeInternal() {} union { - SetVideoStreamingRequest _instance; + SetVideoStreamInfoResponse _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetVideoStreamingRequestDefaultTypeInternal _SetVideoStreamingRequest_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetVideoStreamInfoResponseDefaultTypeInternal _SetVideoStreamInfoResponse_default_instance_; inline constexpr SetInformationResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept @@ -1012,6 +1020,25 @@ struct CaptureInfoDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CaptureInfoDefaultTypeInternal _CaptureInfo_default_instance_; +inline constexpr SetVideoStreamInfoRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : video_stream_infos_{}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR SetVideoStreamInfoRequest::SetVideoStreamInfoRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct SetVideoStreamInfoRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetVideoStreamInfoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetVideoStreamInfoRequestDefaultTypeInternal() {} + union { + SetVideoStreamInfoRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetVideoStreamInfoRequestDefaultTypeInternal _SetVideoStreamInfoRequest_default_instance_; + inline constexpr RespondTakePhotoRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -1034,8 +1061,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[54]; -static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[55]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[9]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( @@ -1060,25 +1087,24 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInformationResponse, _impl_.camera_server_result_), 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingRequest, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingRequest, _internal_metadata_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingRequest, _impl_.video_streaming_), - 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest, _impl_.video_stream_infos_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingResponse, _impl_.camera_server_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse, _impl_.camera_server_result_), 0, ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInProgressRequest, _internal_metadata_), @@ -1488,15 +1514,36 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.definition_file_version_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.definition_file_uri_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreaming, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreaming, _impl_.has_rtsp_server_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreaming, _impl_.rtsp_uri_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _impl_.frame_rate_hz_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _impl_.horizontal_resolution_pix_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _impl_.vertical_resolution_pix_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _impl_.bit_rate_b_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _impl_.rotation_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _impl_.uri_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _impl_.horizontal_fov_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamInfo, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamInfo, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamInfo, _impl_.stream_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamInfo, _impl_.settings_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamInfo, _impl_.status_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamInfo, _impl_.spectrum_), + ~0u, + 0, + ~0u, + ~0u, ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _internal_metadata_), ~0u, // no _extensions_ @@ -1587,65 +1634,66 @@ static const ::_pbi::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { {0, 9, -1, sizeof(::mavsdk::rpc::camera_server::SetInformationRequest)}, {10, 19, -1, sizeof(::mavsdk::rpc::camera_server::SetInformationResponse)}, - {20, 29, -1, sizeof(::mavsdk::rpc::camera_server::SetVideoStreamingRequest)}, - {30, 39, -1, sizeof(::mavsdk::rpc::camera_server::SetVideoStreamingResponse)}, - {40, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressRequest)}, - {49, 58, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, - {59, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, - {67, -1, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, - {76, 86, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - {88, 97, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - {98, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest)}, - {106, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, - {115, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoRequest)}, - {124, 133, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoResponse)}, - {134, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, - {142, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, - {151, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoRequest)}, - {160, 169, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoResponse)}, - {170, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest)}, - {178, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoStreamingResponse)}, - {187, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest)}, - {196, 205, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse)}, - {206, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest)}, - {214, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, - {223, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest)}, - {232, 241, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse)}, - {242, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeSetModeRequest)}, - {250, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetModeResponse)}, - {259, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeRequest)}, - {268, 277, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeResponse)}, - {278, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest)}, - {286, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformationResponse)}, - {295, 305, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationRequest)}, - {307, 316, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationResponse)}, - {317, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest)}, - {325, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatusResponse)}, - {334, 344, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest)}, - {346, 355, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse)}, - {356, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest)}, - {364, -1, -1, sizeof(::mavsdk::rpc::camera_server::FormatStorageResponse)}, - {373, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageRequest)}, - {382, 391, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageResponse)}, - {392, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest)}, - {400, -1, -1, sizeof(::mavsdk::rpc::camera_server::ResetSettingsResponse)}, - {409, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsRequest)}, - {418, 427, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsResponse)}, - {428, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - {447, -1, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreaming)}, - {457, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - {469, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - {481, 495, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - {501, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, - {511, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, - {527, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, + {20, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetVideoStreamInfoRequest)}, + {29, 38, -1, sizeof(::mavsdk::rpc::camera_server::SetVideoStreamInfoResponse)}, + {39, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressRequest)}, + {48, 57, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, + {58, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, + {66, -1, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, + {75, 85, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + {87, 96, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + {97, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest)}, + {105, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, + {114, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoRequest)}, + {123, 132, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoResponse)}, + {133, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, + {141, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, + {150, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoRequest)}, + {159, 168, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoResponse)}, + {169, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest)}, + {177, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoStreamingResponse)}, + {186, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest)}, + {195, 204, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse)}, + {205, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest)}, + {213, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, + {222, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest)}, + {231, 240, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse)}, + {241, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeSetModeRequest)}, + {249, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetModeResponse)}, + {258, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeRequest)}, + {267, 276, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeResponse)}, + {277, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest)}, + {285, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformationResponse)}, + {294, 304, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationRequest)}, + {306, 315, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationResponse)}, + {316, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest)}, + {324, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatusResponse)}, + {333, 343, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest)}, + {345, 354, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse)}, + {355, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest)}, + {363, -1, -1, sizeof(::mavsdk::rpc::camera_server::FormatStorageResponse)}, + {372, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageRequest)}, + {381, 390, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageResponse)}, + {391, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest)}, + {399, -1, -1, sizeof(::mavsdk::rpc::camera_server::ResetSettingsResponse)}, + {408, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsRequest)}, + {417, 426, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsResponse)}, + {427, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + {446, -1, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreamSettings)}, + {461, 473, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreamInfo)}, + {477, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + {489, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + {501, 515, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + {521, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + {531, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, + {547, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, }; static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_SetInformationRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_SetInformationResponse_default_instance_._instance, - &::mavsdk::rpc::camera_server::_SetVideoStreamingRequest_default_instance_._instance, - &::mavsdk::rpc::camera_server::_SetVideoStreamingResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SetVideoStreamInfoRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SetVideoStreamInfoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SetInProgressRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_SetInProgressResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeTakePhotoRequest_default_instance_._instance, @@ -1689,7 +1737,8 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_RespondResetSettingsRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondResetSettingsResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, - &::mavsdk::rpc::camera_server::_VideoStreaming_default_instance_._instance, + &::mavsdk::rpc::camera_server::_VideoStreamSettings_default_instance_._instance, + &::mavsdk::rpc::camera_server::_VideoStreamInfo_default_instance_._instance, &::mavsdk::rpc::camera_server::_Position_default_instance_._instance, &::mavsdk::rpc::camera_server::_Quaternion_default_instance_._instance, &::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_._instance, @@ -1704,236 +1753,252 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "ion\030\001 \001(\0132%.mavsdk.rpc.camera_server.Inf" "ormation\"d\n\026SetInformationResponse\022J\n\024ca" "mera_server_result\030\001 \001(\0132,.mavsdk.rpc.ca" - "mera_server.CameraServerResult\"]\n\030SetVid" - "eoStreamingRequest\022A\n\017video_streaming\030\001 " - "\001(\0132(.mavsdk.rpc.camera_server.VideoStre" - "aming\"g\n\031SetVideoStreamingResponse\022J\n\024ca" - "mera_server_result\030\001 \001(\0132,.mavsdk.rpc.ca" - "mera_server.CameraServerResult\"+\n\024SetInP" - "rogressRequest\022\023\n\013in_progress\030\001 \001(\010\"c\n\025S" - "etInProgressResponse\022J\n\024camera_server_re" - "sult\030\001 \001(\0132,.mavsdk.rpc.camera_server.Ca" - "meraServerResult\"\033\n\031SubscribeTakePhotoRe" - "quest\"\"\n\021TakePhotoResponse\022\r\n\005index\030\001 \001(" - "\005\"\235\001\n\027RespondTakePhotoRequest\022E\n\023take_ph" - "oto_feedback\030\001 \001(\0162(.mavsdk.rpc.camera_s" - "erver.CameraFeedback\022;\n\014capture_info\030\002 \001" - "(\0132%.mavsdk.rpc.camera_server.CaptureInf" - "o\"f\n\030RespondTakePhotoResponse\022J\n\024camera_" + "mera_server.CameraServerResult\"b\n\031SetVid" + "eoStreamInfoRequest\022E\n\022video_stream_info" + "s\030\001 \003(\0132).mavsdk.rpc.camera_server.Video" + "StreamInfo\"h\n\032SetVideoStreamInfoResponse" + "\022J\n\024camera_server_result\030\001 \001(\0132,.mavsdk." + "rpc.camera_server.CameraServerResult\"+\n\024" + "SetInProgressRequest\022\023\n\013in_progress\030\001 \001(" + "\010\"c\n\025SetInProgressResponse\022J\n\024camera_ser" + "ver_result\030\001 \001(\0132,.mavsdk.rpc.camera_ser" + "ver.CameraServerResult\"\033\n\031SubscribeTakeP" + "hotoRequest\"\"\n\021TakePhotoResponse\022\r\n\005inde" + "x\030\001 \001(\005\"\235\001\n\027RespondTakePhotoRequest\022E\n\023t" + "ake_photo_feedback\030\001 \001(\0162(.mavsdk.rpc.ca" + "mera_server.CameraFeedback\022;\n\014capture_in" + "fo\030\002 \001(\0132%.mavsdk.rpc.camera_server.Capt" + "ureInfo\"f\n\030RespondTakePhotoResponse\022J\n\024c" + "amera_server_result\030\001 \001(\0132,.mavsdk.rpc.c" + "amera_server.CameraServerResult\"\034\n\032Subsc" + "ribeStartVideoRequest\"\'\n\022StartVideoRespo" + "nse\022\021\n\tstream_id\030\001 \001(\005\"b\n\030RespondStartVi" + "deoRequest\022F\n\024start_video_feedback\030\001 \001(\016" + "2(.mavsdk.rpc.camera_server.CameraFeedba" + "ck\"g\n\031RespondStartVideoResponse\022J\n\024camer" + "a_server_result\030\001 \001(\0132,.mavsdk.rpc.camer" + "a_server.CameraServerResult\"\033\n\031Subscribe" + "StopVideoRequest\"&\n\021StopVideoResponse\022\021\n" + "\tstream_id\030\001 \001(\005\"`\n\027RespondStopVideoRequ" + "est\022E\n\023stop_video_feedback\030\001 \001(\0162(.mavsd" + "k.rpc.camera_server.CameraFeedback\"f\n\030Re" + "spondStopVideoResponse\022J\n\024camera_server_" + "result\030\001 \001(\0132,.mavsdk.rpc.camera_server." + "CameraServerResult\"%\n#SubscribeStartVide" + "oStreamingRequest\"0\n\033StartVideoStreaming" + "Response\022\021\n\tstream_id\030\001 \001(\005\"u\n!RespondSt" + "artVideoStreamingRequest\022P\n\036start_video_" + "streaming_feedback\030\001 \001(\0162(.mavsdk.rpc.ca" + "mera_server.CameraFeedback\"p\n\"RespondSta" + "rtVideoStreamingResponse\022J\n\024camera_serve" + "r_result\030\001 \001(\0132,.mavsdk.rpc.camera_serve" + "r.CameraServerResult\"$\n\"SubscribeStopVid" + "eoStreamingRequest\"/\n\032StopVideoStreaming" + "Response\022\021\n\tstream_id\030\001 \001(\005\"s\n RespondSt" + "opVideoStreamingRequest\022O\n\035stop_video_st" + "reaming_feedback\030\001 \001(\0162(.mavsdk.rpc.came" + "ra_server.CameraFeedback\"o\n!RespondStopV" + "ideoStreamingResponse\022J\n\024camera_server_r" + "esult\030\001 \001(\0132,.mavsdk.rpc.camera_server.C" + "ameraServerResult\"\031\n\027SubscribeSetModeReq" + "uest\"\?\n\017SetModeResponse\022,\n\004mode\030\001 \001(\0162\036." + "mavsdk.rpc.camera_server.Mode\"\\\n\025Respond" + "SetModeRequest\022C\n\021set_mode_feedback\030\001 \001(" + "\0162(.mavsdk.rpc.camera_server.CameraFeedb" + "ack\"d\n\026RespondSetModeResponse\022J\n\024camera_" "server_result\030\001 \001(\0132,.mavsdk.rpc.camera_" - "server.CameraServerResult\"\034\n\032SubscribeSt" - "artVideoRequest\"\'\n\022StartVideoResponse\022\021\n" - "\tstream_id\030\001 \001(\005\"b\n\030RespondStartVideoReq" - "uest\022F\n\024start_video_feedback\030\001 \001(\0162(.mav" - "sdk.rpc.camera_server.CameraFeedback\"g\n\031" - "RespondStartVideoResponse\022J\n\024camera_serv" - "er_result\030\001 \001(\0132,.mavsdk.rpc.camera_serv" - "er.CameraServerResult\"\033\n\031SubscribeStopVi" - "deoRequest\"&\n\021StopVideoResponse\022\021\n\tstrea" - "m_id\030\001 \001(\005\"`\n\027RespondStopVideoRequest\022E\n" - "\023stop_video_feedback\030\001 \001(\0162(.mavsdk.rpc." - "camera_server.CameraFeedback\"f\n\030RespondS" - "topVideoResponse\022J\n\024camera_server_result" - "\030\001 \001(\0132,.mavsdk.rpc.camera_server.Camera" - "ServerResult\"%\n#SubscribeStartVideoStrea" - "mingRequest\"0\n\033StartVideoStreamingRespon" - "se\022\021\n\tstream_id\030\001 \001(\005\"u\n!RespondStartVid" - "eoStreamingRequest\022P\n\036start_video_stream" - "ing_feedback\030\001 \001(\0162(.mavsdk.rpc.camera_s" - "erver.CameraFeedback\"p\n\"RespondStartVide" - "oStreamingResponse\022J\n\024camera_server_resu" + "server.CameraServerResult\"$\n\"SubscribeSt" + "orageInformationRequest\"0\n\032StorageInform" + "ationResponse\022\022\n\nstorage_id\030\001 \001(\005\"\275\001\n Re" + "spondStorageInformationRequest\022N\n\034storag" + "e_information_feedback\030\001 \001(\0162(.mavsdk.rp" + "c.camera_server.CameraFeedback\022I\n\023storag" + "e_information\030\002 \001(\0132,.mavsdk.rpc.camera_" + "server.StorageInformation\"o\n!RespondStor" + "ageInformationResponse\022J\n\024camera_server_" + "result\030\001 \001(\0132,.mavsdk.rpc.camera_server." + "CameraServerResult\"\037\n\035SubscribeCaptureSt" + "atusRequest\")\n\025CaptureStatusResponse\022\020\n\010" + "reserved\030\001 \001(\005\"\251\001\n\033RespondCaptureStatusR" + "equest\022I\n\027capture_status_feedback\030\001 \001(\0162" + "(.mavsdk.rpc.camera_server.CameraFeedbac" + "k\022\?\n\016capture_status\030\002 \001(\0132\'.mavsdk.rpc.c" + "amera_server.CaptureStatus\"j\n\034RespondCap" + "tureStatusResponse\022J\n\024camera_server_resu" "lt\030\001 \001(\0132,.mavsdk.rpc.camera_server.Came" - "raServerResult\"$\n\"SubscribeStopVideoStre" - "amingRequest\"/\n\032StopVideoStreamingRespon" - "se\022\021\n\tstream_id\030\001 \001(\005\"s\n RespondStopVide" - "oStreamingRequest\022O\n\035stop_video_streamin" - "g_feedback\030\001 \001(\0162(.mavsdk.rpc.camera_ser" - "ver.CameraFeedback\"o\n!RespondStopVideoSt" - "reamingResponse\022J\n\024camera_server_result\030" - "\001 \001(\0132,.mavsdk.rpc.camera_server.CameraS" - "erverResult\"\031\n\027SubscribeSetModeRequest\"\?" - "\n\017SetModeResponse\022,\n\004mode\030\001 \001(\0162\036.mavsdk" - ".rpc.camera_server.Mode\"\\\n\025RespondSetMod" - "eRequest\022C\n\021set_mode_feedback\030\001 \001(\0162(.ma" - "vsdk.rpc.camera_server.CameraFeedback\"d\n" - "\026RespondSetModeResponse\022J\n\024camera_server" - "_result\030\001 \001(\0132,.mavsdk.rpc.camera_server" - ".CameraServerResult\"$\n\"SubscribeStorageI" - "nformationRequest\"0\n\032StorageInformationR" - "esponse\022\022\n\nstorage_id\030\001 \001(\005\"\275\001\n RespondS" - "torageInformationRequest\022N\n\034storage_info" - "rmation_feedback\030\001 \001(\0162(.mavsdk.rpc.came" - "ra_server.CameraFeedback\022I\n\023storage_info" - "rmation\030\002 \001(\0132,.mavsdk.rpc.camera_server" - ".StorageInformation\"o\n!RespondStorageInf" - "ormationResponse\022J\n\024camera_server_result" - "\030\001 \001(\0132,.mavsdk.rpc.camera_server.Camera" - "ServerResult\"\037\n\035SubscribeCaptureStatusRe" - "quest\")\n\025CaptureStatusResponse\022\020\n\010reserv" - "ed\030\001 \001(\005\"\251\001\n\033RespondCaptureStatusRequest" - "\022I\n\027capture_status_feedback\030\001 \001(\0162(.mavs" - "dk.rpc.camera_server.CameraFeedback\022\?\n\016c" - "apture_status\030\002 \001(\0132\'.mavsdk.rpc.camera_" - "server.CaptureStatus\"j\n\034RespondCaptureSt" - "atusResponse\022J\n\024camera_server_result\030\001 \001" - "(\0132,.mavsdk.rpc.camera_server.CameraServ" - "erResult\"\037\n\035SubscribeFormatStorageReques" - "t\"+\n\025FormatStorageResponse\022\022\n\nstorage_id" - "\030\001 \001(\005\"h\n\033RespondFormatStorageRequest\022I\n" - "\027format_storage_feedback\030\001 \001(\0162(.mavsdk." - "rpc.camera_server.CameraFeedback\"j\n\034Resp" - "ondFormatStorageResponse\022J\n\024camera_serve" - "r_result\030\001 \001(\0132,.mavsdk.rpc.camera_serve" - "r.CameraServerResult\"\037\n\035SubscribeResetSe" - "ttingsRequest\")\n\025ResetSettingsResponse\022\020" - "\n\010reserved\030\001 \001(\005\"h\n\033RespondResetSettings" - "Request\022I\n\027reset_settings_feedback\030\001 \001(\016" - "2(.mavsdk.rpc.camera_server.CameraFeedba" - "ck\"j\n\034RespondResetSettingsResponse\022J\n\024ca" - "mera_server_result\030\001 \001(\0132,.mavsdk.rpc.ca" - "mera_server.CameraServerResult\"\276\002\n\013Infor" - "mation\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_nam" - "e\030\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017foc" - "al_length_mm\030\004 \001(\002\022!\n\031horizontal_sensor_" - "size_mm\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm" - "\030\006 \001(\002\022 \n\030horizontal_resolution_px\030\007 \001(\r" - "\022\036\n\026vertical_resolution_px\030\010 \001(\r\022\017\n\007lens" - "_id\030\t \001(\r\022\037\n\027definition_file_version\030\n \001" - "(\r\022\033\n\023definition_file_uri\030\013 \001(\t\";\n\016Video" - "Streaming\022\027\n\017has_rtsp_server\030\001 \001(\010\022\020\n\010rt" - "sp_uri\030\002 \001(\t\"q\n\010Position\022\024\n\014latitude_deg" - "\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolut" - "e_altitude_m\030\003 \001(\002\022\033\n\023relative_altitude_" - "m\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 " - "\001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInf" - "o\0224\n\010position\030\001 \001(\0132\".mavsdk.rpc.camera_" - "server.Position\022A\n\023attitude_quaternion\030\002" - " \001(\0132$.mavsdk.rpc.camera_server.Quaterni" - "on\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 " - "\001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n" - "\022CameraServerResult\022C\n\006result\030\001 \001(\01623.ma" - "vsdk.rpc.camera_server.CameraServerResul" - "t.Result\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022" - "\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022" - "\026\n\022RESULT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003" - "\022\021\n\rRESULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n" - "\016RESULT_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUME" - "NT\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010\"\214\005\n\022StorageIn" - "formation\022\030\n\020used_storage_mib\030\001 \001(\002\022\035\n\025a" - "vailable_storage_mib\030\002 \001(\002\022\031\n\021total_stor" - "age_mib\030\003 \001(\002\022R\n\016storage_status\030\004 \001(\0162:." - "mavsdk.rpc.camera_server.StorageInformat" - "ion.StorageStatus\022\022\n\nstorage_id\030\005 \001(\r\022N\n" - "\014storage_type\030\006 \001(\01628.mavsdk.rpc.camera_" - "server.StorageInformation.StorageType\022\030\n" - "\020read_speed_mib_s\030\007 \001(\002\022\031\n\021write_speed_m" - "ib_s\030\010 \001(\002\"\221\001\n\rStorageStatus\022 \n\034STORAGE_" - "STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS" - "_UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATT" - "ED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240" - "\001\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000" - "\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_" - "TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017S" - "TORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376" - "\001\"\356\003\n\rCaptureStatus\022\030\n\020image_interval_s\030" - "\001 \001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\036\n\026avail" - "able_capacity_mib\030\003 \001(\002\022I\n\014image_status\030" - "\004 \001(\01623.mavsdk.rpc.camera_server.Capture" - "Status.ImageStatus\022I\n\014video_status\030\005 \001(\016" - "23.mavsdk.rpc.camera_server.CaptureStatu" - "s.VideoStatus\022\023\n\013image_count\030\006 \001(\005\"\221\001\n\013I" - "mageStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$\n IMA" - "GE_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032IMAGE" - "_STATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_STATUS_" - "INTERVAL_IN_PROGRESS\020\003\"J\n\013VideoStatus\022\025\n" - "\021VIDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATUS_CAP" - "TURE_IN_PROGRESS\020\001*{\n\016CameraFeedback\022\033\n\027" - "CAMERA_FEEDBACK_UNKNOWN\020\000\022\026\n\022CAMERA_FEED" - "BACK_OK\020\001\022\030\n\024CAMERA_FEEDBACK_BUSY\020\002\022\032\n\026C" - "AMERA_FEEDBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_" - "UNKNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020" - "\0022\217\031\n\023CameraServerService\022y\n\016SetInformat" - "ion\022/.mavsdk.rpc.camera_server.SetInform" - "ationRequest\0320.mavsdk.rpc.camera_server." - "SetInformationResponse\"\004\200\265\030\001\022\202\001\n\021SetVide" - "oStreaming\0222.mavsdk.rpc.camera_server.Se" - "tVideoStreamingRequest\0323.mavsdk.rpc.came" - "ra_server.SetVideoStreamingResponse\"\004\200\265\030" - "\001\022v\n\rSetInProgress\022..mavsdk.rpc.camera_s" - "erver.SetInProgressRequest\032/.mavsdk.rpc." - "camera_server.SetInProgressResponse\"\004\200\265\030" - "\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rpc.cam" - "era_server.SubscribeTakePhotoRequest\032+.m" - "avsdk.rpc.camera_server.TakePhotoRespons" - "e\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk.r" - "pc.camera_server.RespondTakePhotoRequest" - "\0322.mavsdk.rpc.camera_server.RespondTakeP" - "hotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVid" - "eo\0224.mavsdk.rpc.camera_server.SubscribeS" - "tartVideoRequest\032,.mavsdk.rpc.camera_ser" - "ver.StartVideoResponse\"\004\200\265\030\0000\001\022\202\001\n\021Respo" - "ndStartVideo\0222.mavsdk.rpc.camera_server." - "RespondStartVideoRequest\0323.mavsdk.rpc.ca" - "mera_server.RespondStartVideoResponse\"\004\200" - "\265\030\001\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc.c" - "amera_server.SubscribeStopVideoRequest\032+" - ".mavsdk.rpc.camera_server.StopVideoRespo" - "nse\"\004\200\265\030\0000\001\022\177\n\020RespondStopVideo\0221.mavsdk" - ".rpc.camera_server.RespondStopVideoReque" - "st\0322.mavsdk.rpc.camera_server.RespondSto" - "pVideoResponse\"\004\200\265\030\001\022\234\001\n\034SubscribeStartV" - "ideoStreaming\022=.mavsdk.rpc.camera_server" - ".SubscribeStartVideoStreamingRequest\0325.m" - "avsdk.rpc.camera_server.StartVideoStream" - "ingResponse\"\004\200\265\030\0000\001\022\235\001\n\032RespondStartVide" - "oStreaming\022;.mavsdk.rpc.camera_server.Re" - "spondStartVideoStreamingRequest\032<.mavsdk" - ".rpc.camera_server.RespondStartVideoStre" - "amingResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStopVid" - "eoStreaming\022<.mavsdk.rpc.camera_server.S" - "ubscribeStopVideoStreamingRequest\0324.mavs" - "dk.rpc.camera_server.StopVideoStreamingR" - "esponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStopVideoStre" - "aming\022:.mavsdk.rpc.camera_server.Respond" - "StopVideoStreamingRequest\032;.mavsdk.rpc.c" - "amera_server.RespondStopVideoStreamingRe" - "sponse\"\004\200\265\030\001\022x\n\020SubscribeSetMode\0221.mavsd" - "k.rpc.camera_server.SubscribeSetModeRequ" - "est\032).mavsdk.rpc.camera_server.SetModeRe" - "sponse\"\004\200\265\030\0000\001\022y\n\016RespondSetMode\022/.mavsd" - "k.rpc.camera_server.RespondSetModeReques" - "t\0320.mavsdk.rpc.camera_server.RespondSetM" - "odeResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStorageIn" - "formation\022<.mavsdk.rpc.camera_server.Sub" - "scribeStorageInformationRequest\0324.mavsdk" - ".rpc.camera_server.StorageInformationRes" - "ponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInformat" - "ion\022:.mavsdk.rpc.camera_server.RespondSt" - "orageInformationRequest\032;.mavsdk.rpc.cam" - "era_server.RespondStorageInformationResp" - "onse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\0227." - "mavsdk.rpc.camera_server.SubscribeCaptur" - "eStatusRequest\032/.mavsdk.rpc.camera_serve" - "r.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024Resp" - "ondCaptureStatus\0225.mavsdk.rpc.camera_ser" - "ver.RespondCaptureStatusRequest\0326.mavsdk" - ".rpc.camera_server.RespondCaptureStatusR" - "esponse\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatStorage" - "\0227.mavsdk.rpc.camera_server.SubscribeFor" - "matStorageRequest\032/.mavsdk.rpc.camera_se" - "rver.FormatStorageResponse\"\004\200\265\030\0000\001\022\213\001\n\024R" - "espondFormatStorage\0225.mavsdk.rpc.camera_" - "server.RespondFormatStorageRequest\0326.mav" - "sdk.rpc.camera_server.RespondFormatStora" - "geResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeResetSetti" - "ngs\0227.mavsdk.rpc.camera_server.Subscribe" - "ResetSettingsRequest\032/.mavsdk.rpc.camera" - "_server.ResetSettingsResponse\"\004\200\265\030\0000\001\022\213\001" - "\n\024RespondResetSettings\0225.mavsdk.rpc.came" - "ra_server.RespondResetSettingsRequest\0326." - "mavsdk.rpc.camera_server.RespondResetSet" - "tingsResponse\"\004\200\265\030\001B,\n\027io.mavsdk.camera_" - "serverB\021CameraServerProtob\006proto3" + "raServerResult\"\037\n\035SubscribeFormatStorage" + "Request\"+\n\025FormatStorageResponse\022\022\n\nstor" + "age_id\030\001 \001(\005\"h\n\033RespondFormatStorageRequ" + "est\022I\n\027format_storage_feedback\030\001 \001(\0162(.m" + "avsdk.rpc.camera_server.CameraFeedback\"j" + "\n\034RespondFormatStorageResponse\022J\n\024camera" + "_server_result\030\001 \001(\0132,.mavsdk.rpc.camera" + "_server.CameraServerResult\"\037\n\035SubscribeR" + "esetSettingsRequest\")\n\025ResetSettingsResp" + "onse\022\020\n\010reserved\030\001 \001(\005\"h\n\033RespondResetSe" + "ttingsRequest\022I\n\027reset_settings_feedback" + "\030\001 \001(\0162(.mavsdk.rpc.camera_server.Camera" + "Feedback\"j\n\034RespondResetSettingsResponse" + "\022J\n\024camera_server_result\030\001 \001(\0132,.mavsdk." + "rpc.camera_server.CameraServerResult\"\276\002\n" + "\013Information\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmod" + "el_name\030\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022" + "\027\n\017focal_length_mm\030\004 \001(\002\022!\n\031horizontal_s" + "ensor_size_mm\030\005 \001(\002\022\037\n\027vertical_sensor_s" + "ize_mm\030\006 \001(\002\022 \n\030horizontal_resolution_px" + "\030\007 \001(\r\022\036\n\026vertical_resolution_px\030\010 \001(\r\022\017" + "\n\007lens_id\030\t \001(\r\022\037\n\027definition_file_versi" + "on\030\n \001(\r\022\033\n\023definition_file_uri\030\013 \001(\t\"\305\001" + "\n\023VideoStreamSettings\022\025\n\rframe_rate_hz\030\001" + " \001(\002\022!\n\031horizontal_resolution_pix\030\002 \001(\r\022" + "\037\n\027vertical_resolution_pix\030\003 \001(\r\022\024\n\014bit_" + "rate_b_s\030\004 \001(\r\022\024\n\014rotation_deg\030\005 \001(\r\022\013\n\003" + "uri\030\006 \001(\t\022\032\n\022horizontal_fov_deg\030\007 \001(\002\"\352\003" + "\n\017VideoStreamInfo\022\021\n\tstream_id\030\001 \001(\005\022\?\n\010" + "settings\030\002 \001(\0132-.mavsdk.rpc.camera_serve" + "r.VideoStreamSettings\022K\n\006status\030\003 \001(\0162;." + "mavsdk.rpc.camera_server.VideoStreamInfo" + ".VideoStreamStatus\022O\n\010spectrum\030\004 \001(\0162=.m" + "avsdk.rpc.camera_server.VideoStreamInfo." + "VideoStreamSpectrum\"]\n\021VideoStreamStatus" + "\022#\n\037VIDEO_STREAM_STATUS_NOT_RUNNING\020\000\022#\n" + "\037VIDEO_STREAM_STATUS_IN_PROGRESS\020\001\"\205\001\n\023V" + "ideoStreamSpectrum\022!\n\035VIDEO_STREAM_SPECT" + "RUM_UNKNOWN\020\000\022\'\n#VIDEO_STREAM_SPECTRUM_V" + "ISIBLE_LIGHT\020\001\022\"\n\036VIDEO_STREAM_SPECTRUM_" + "INFRARED\020\002\"q\n\010Position\022\024\n\014latitude_deg\030\001" + " \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_" + "altitude_m\030\003 \001(\002\022\033\n\023relative_altitude_m\030" + "\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(" + "\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\022" + "4\n\010position\030\001 \001(\0132\".mavsdk.rpc.camera_se" + "rver.Position\022A\n\023attitude_quaternion\030\002 \001" + "(\0132$.mavsdk.rpc.camera_server.Quaternion" + "\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(" + "\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022C" + "ameraServerResult\022C\n\006result\030\001 \001(\01623.mavs" + "dk.rpc.camera_server.CameraServerResult." + "Result\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n" + "\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n" + "\022RESULT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021" + "\n\rRESULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016R" + "ESULT_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT" + "\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010\"\214\005\n\022StorageInfo" + "rmation\022\030\n\020used_storage_mib\030\001 \001(\002\022\035\n\025ava" + "ilable_storage_mib\030\002 \001(\002\022\031\n\021total_storag" + "e_mib\030\003 \001(\002\022R\n\016storage_status\030\004 \001(\0162:.ma" + "vsdk.rpc.camera_server.StorageInformatio" + "n.StorageStatus\022\022\n\nstorage_id\030\005 \001(\r\022N\n\014s" + "torage_type\030\006 \001(\01628.mavsdk.rpc.camera_se" + "rver.StorageInformation.StorageType\022\030\n\020r" + "ead_speed_mib_s\030\007 \001(\002\022\031\n\021write_speed_mib" + "_s\030\010 \001(\002\"\221\001\n\rStorageStatus\022 \n\034STORAGE_ST" + "ATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS_U" + "NFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATTED" + "\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240\001\n" + "\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000\022\032" + "\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_TY" + "PE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017STO" + "RAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376\001\"" + "\356\003\n\rCaptureStatus\022\030\n\020image_interval_s\030\001 " + "\001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\036\n\026availab" + "le_capacity_mib\030\003 \001(\002\022I\n\014image_status\030\004 " + "\001(\01623.mavsdk.rpc.camera_server.CaptureSt" + "atus.ImageStatus\022I\n\014video_status\030\005 \001(\01623" + ".mavsdk.rpc.camera_server.CaptureStatus." + "VideoStatus\022\023\n\013image_count\030\006 \001(\005\"\221\001\n\013Ima" + "geStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$\n IMAGE" + "_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032IMAGE_S" + "TATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_STATUS_IN" + "TERVAL_IN_PROGRESS\020\003\"J\n\013VideoStatus\022\025\n\021V" + "IDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATUS_CAPTU" + "RE_IN_PROGRESS\020\001*{\n\016CameraFeedback\022\033\n\027CA" + "MERA_FEEDBACK_UNKNOWN\020\000\022\026\n\022CAMERA_FEEDBA" + "CK_OK\020\001\022\030\n\024CAMERA_FEEDBACK_BUSY\020\002\022\032\n\026CAM" + "ERA_FEEDBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_UN" + "KNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\0022" + "\222\031\n\023CameraServerService\022y\n\016SetInformatio" + "n\022/.mavsdk.rpc.camera_server.SetInformat" + "ionRequest\0320.mavsdk.rpc.camera_server.Se" + "tInformationResponse\"\004\200\265\030\001\022\205\001\n\022SetVideoS" + "treamInfo\0223.mavsdk.rpc.camera_server.Set" + "VideoStreamInfoRequest\0324.mavsdk.rpc.came" + "ra_server.SetVideoStreamInfoResponse\"\004\200\265" + "\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.camera_" + "server.SetInProgressRequest\032/.mavsdk.rpc" + ".camera_server.SetInProgressResponse\"\004\200\265" + "\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rpc.ca" + "mera_server.SubscribeTakePhotoRequest\032+." + "mavsdk.rpc.camera_server.TakePhotoRespon" + "se\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk." + "rpc.camera_server.RespondTakePhotoReques" + "t\0322.mavsdk.rpc.camera_server.RespondTake" + "PhotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVi" + "deo\0224.mavsdk.rpc.camera_server.Subscribe" + "StartVideoRequest\032,.mavsdk.rpc.camera_se" + "rver.StartVideoResponse\"\004\200\265\030\0000\001\022\202\001\n\021Resp" + "ondStartVideo\0222.mavsdk.rpc.camera_server" + ".RespondStartVideoRequest\0323.mavsdk.rpc.c" + "amera_server.RespondStartVideoResponse\"\004" + "\200\265\030\001\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc." + "camera_server.SubscribeStopVideoRequest\032" + "+.mavsdk.rpc.camera_server.StopVideoResp" + "onse\"\004\200\265\030\0000\001\022\177\n\020RespondStopVideo\0221.mavsd" + "k.rpc.camera_server.RespondStopVideoRequ" + "est\0322.mavsdk.rpc.camera_server.RespondSt" + "opVideoResponse\"\004\200\265\030\001\022\234\001\n\034SubscribeStart" + "VideoStreaming\022=.mavsdk.rpc.camera_serve" + "r.SubscribeStartVideoStreamingRequest\0325." + "mavsdk.rpc.camera_server.StartVideoStrea" + "mingResponse\"\004\200\265\030\0000\001\022\235\001\n\032RespondStartVid" + "eoStreaming\022;.mavsdk.rpc.camera_server.R" + "espondStartVideoStreamingRequest\032<.mavsd" + "k.rpc.camera_server.RespondStartVideoStr" + "eamingResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStopVi" + "deoStreaming\022<.mavsdk.rpc.camera_server." + "SubscribeStopVideoStreamingRequest\0324.mav" + "sdk.rpc.camera_server.StopVideoStreaming" + "Response\"\004\200\265\030\0000\001\022\232\001\n\031RespondStopVideoStr" + "eaming\022:.mavsdk.rpc.camera_server.Respon" + "dStopVideoStreamingRequest\032;.mavsdk.rpc." + "camera_server.RespondStopVideoStreamingR" + "esponse\"\004\200\265\030\001\022x\n\020SubscribeSetMode\0221.mavs" + "dk.rpc.camera_server.SubscribeSetModeReq" + "uest\032).mavsdk.rpc.camera_server.SetModeR" + "esponse\"\004\200\265\030\0000\001\022y\n\016RespondSetMode\022/.mavs" + "dk.rpc.camera_server.RespondSetModeReque" + "st\0320.mavsdk.rpc.camera_server.RespondSet" + "ModeResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStorageI" + "nformation\022<.mavsdk.rpc.camera_server.Su" + "bscribeStorageInformationRequest\0324.mavsd" + "k.rpc.camera_server.StorageInformationRe" + "sponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInforma" + "tion\022:.mavsdk.rpc.camera_server.RespondS" + "torageInformationRequest\032;.mavsdk.rpc.ca" + "mera_server.RespondStorageInformationRes" + "ponse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\0227" + ".mavsdk.rpc.camera_server.SubscribeCaptu" + "reStatusRequest\032/.mavsdk.rpc.camera_serv" + "er.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024Res" + "pondCaptureStatus\0225.mavsdk.rpc.camera_se" + "rver.RespondCaptureStatusRequest\0326.mavsd" + "k.rpc.camera_server.RespondCaptureStatus" + "Response\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatStorag" + "e\0227.mavsdk.rpc.camera_server.SubscribeFo" + "rmatStorageRequest\032/.mavsdk.rpc.camera_s" + "erver.FormatStorageResponse\"\004\200\265\030\0000\001\022\213\001\n\024" + "RespondFormatStorage\0225.mavsdk.rpc.camera" + "_server.RespondFormatStorageRequest\0326.ma" + "vsdk.rpc.camera_server.RespondFormatStor" + "ageResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeResetSett" + "ings\0227.mavsdk.rpc.camera_server.Subscrib" + "eResetSettingsRequest\032/.mavsdk.rpc.camer" + "a_server.ResetSettingsResponse\"\004\200\265\030\0000\001\022\213" + "\001\n\024RespondResetSettings\0225.mavsdk.rpc.cam" + "era_server.RespondResetSettingsRequest\0326" + ".mavsdk.rpc.camera_server.RespondResetSe" + "ttingsResponse\"\004\200\265\030\001B,\n\027io.mavsdk.camera" + "_serverB\021CameraServerProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -1943,13 +2008,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 9433, + 10074, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 54, + 55, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -1978,10 +2043,51 @@ static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_camera_5fserver_2fcamera_ namespace mavsdk { namespace rpc { namespace camera_server { -const ::google::protobuf::EnumDescriptor* CameraServerResult_Result_descriptor() { +const ::google::protobuf::EnumDescriptor* VideoStreamInfo_VideoStreamStatus_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[0]; } +PROTOBUF_CONSTINIT const uint32_t VideoStreamInfo_VideoStreamStatus_internal_data_[] = { + 131072u, 0u, }; +bool VideoStreamInfo_VideoStreamStatus_IsValid(int value) { + return 0 <= value && value <= 1; +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr VideoStreamInfo_VideoStreamStatus VideoStreamInfo::VIDEO_STREAM_STATUS_NOT_RUNNING; +constexpr VideoStreamInfo_VideoStreamStatus VideoStreamInfo::VIDEO_STREAM_STATUS_IN_PROGRESS; +constexpr VideoStreamInfo_VideoStreamStatus VideoStreamInfo::VideoStreamStatus_MIN; +constexpr VideoStreamInfo_VideoStreamStatus VideoStreamInfo::VideoStreamStatus_MAX; +constexpr int VideoStreamInfo::VideoStreamStatus_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::google::protobuf::EnumDescriptor* VideoStreamInfo_VideoStreamSpectrum_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[1]; +} +PROTOBUF_CONSTINIT const uint32_t VideoStreamInfo_VideoStreamSpectrum_internal_data_[] = { + 196608u, 0u, }; +bool VideoStreamInfo_VideoStreamSpectrum_IsValid(int value) { + return 0 <= value && value <= 2; +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo::VIDEO_STREAM_SPECTRUM_UNKNOWN; +constexpr VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo::VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT; +constexpr VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo::VIDEO_STREAM_SPECTRUM_INFRARED; +constexpr VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo::VideoStreamSpectrum_MIN; +constexpr VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo::VideoStreamSpectrum_MAX; +constexpr int VideoStreamInfo::VideoStreamSpectrum_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::google::protobuf::EnumDescriptor* CameraServerResult_Result_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; +} PROTOBUF_CONSTINIT const uint32_t CameraServerResult_Result_internal_data_[] = { 589824u, 0u, }; bool CameraServerResult_Result_IsValid(int value) { @@ -2007,7 +2113,7 @@ constexpr int CameraServerResult::Result_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* StorageInformation_StorageStatus_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[1]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[3]; } PROTOBUF_CONSTINIT const uint32_t StorageInformation_StorageStatus_internal_data_[] = { 262144u, 0u, }; @@ -2029,7 +2135,7 @@ constexpr int StorageInformation::StorageStatus_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* StorageInformation_StorageType_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[4]; } PROTOBUF_CONSTINIT const uint32_t StorageInformation_StorageType_internal_data_[] = { 262144u, 65568u, 8u, 254u, }; @@ -2053,7 +2159,7 @@ constexpr int StorageInformation::StorageType_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* CaptureStatus_ImageStatus_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[3]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[5]; } PROTOBUF_CONSTINIT const uint32_t CaptureStatus_ImageStatus_internal_data_[] = { 262144u, 0u, }; @@ -2075,7 +2181,7 @@ constexpr int CaptureStatus::ImageStatus_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* CaptureStatus_VideoStatus_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[4]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[6]; } PROTOBUF_CONSTINIT const uint32_t CaptureStatus_VideoStatus_internal_data_[] = { 131072u, 0u, }; @@ -2095,7 +2201,7 @@ constexpr int CaptureStatus::VideoStatus_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* CameraFeedback_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[5]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; } PROTOBUF_CONSTINIT const uint32_t CameraFeedback_internal_data_[] = { 262144u, 0u, }; @@ -2104,7 +2210,7 @@ bool CameraFeedback_IsValid(int value) { } const ::google::protobuf::EnumDescriptor* Mode_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[6]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[8]; } PROTOBUF_CONSTINIT const uint32_t Mode_internal_data_[] = { 196608u, 0u, }; @@ -2527,84 +2633,64 @@ ::google::protobuf::Metadata SetInformationResponse::GetMetadata() const { } // =================================================================== -class SetVideoStreamingRequest::_Internal { +class SetVideoStreamInfoRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(SetVideoStreamingRequest, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::VideoStreaming& video_streaming(const SetVideoStreamingRequest* msg); - static void set_has_video_streaming(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera_server::VideoStreaming& SetVideoStreamingRequest::_Internal::video_streaming(const SetVideoStreamingRequest* msg) { - return *msg->_impl_.video_streaming_; -} -SetVideoStreamingRequest::SetVideoStreamingRequest(::google::protobuf::Arena* arena) +SetVideoStreamInfoRequest::SetVideoStreamInfoRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) } -inline PROTOBUF_NDEBUG_INLINE SetVideoStreamingRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetVideoStreamInfoRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) - : _has_bits_{from._has_bits_}, + : video_stream_infos_{visibility, arena, from.video_stream_infos_}, _cached_size_{0} {} -SetVideoStreamingRequest::SetVideoStreamingRequest( +SetVideoStreamInfoRequest::SetVideoStreamInfoRequest( ::google::protobuf::Arena* arena, - const SetVideoStreamingRequest& from) + const SetVideoStreamInfoRequest& from) : ::google::protobuf::Message(arena) { - SetVideoStreamingRequest* const _this = this; + SetVideoStreamInfoRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.video_streaming_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera_server::VideoStreaming>(arena, *from._impl_.video_streaming_) - : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) } -inline PROTOBUF_NDEBUG_INLINE SetVideoStreamingRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetVideoStreamInfoRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : _cached_size_{0} {} + : video_stream_infos_{visibility, arena}, + _cached_size_{0} {} -inline void SetVideoStreamingRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetVideoStreamInfoRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.video_streaming_ = {}; } -SetVideoStreamingRequest::~SetVideoStreamingRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetVideoStreamingRequest) +SetVideoStreamInfoRequest::~SetVideoStreamInfoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetVideoStreamingRequest::SharedDtor() { +inline void SetVideoStreamInfoRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.video_streaming_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetVideoStreamingRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) +PROTOBUF_NOINLINE void SetVideoStreamInfoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.video_streaming_ != nullptr); - _impl_.video_streaming_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.video_stream_infos_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetVideoStreamingRequest::_InternalParse( +const char* SetVideoStreamInfoRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -2612,9 +2698,9 @@ const char* SetVideoStreamingRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetVideoStreamingRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetVideoStreamInfoRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetVideoStreamingRequest, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -2623,37 +2709,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetVideoStreamingRequest::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetVideoStreamingRequest_default_instance_._instance, + &_SetVideoStreamInfoRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetVideoStreamingRequest, _impl_.video_streaming_)}}, + // repeated .mavsdk.rpc.camera_server.VideoStreamInfo video_stream_infos = 1; + {::_pbi::TcParser::FastMtR1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(SetVideoStreamInfoRequest, _impl_.video_stream_infos_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; - {PROTOBUF_FIELD_OFFSET(SetVideoStreamingRequest, _impl_.video_streaming_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // repeated .mavsdk.rpc.camera_server.VideoStreamInfo video_stream_infos = 1; + {PROTOBUF_FIELD_OFFSET(SetVideoStreamInfoRequest, _impl_.video_stream_infos_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::VideoStreaming>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::VideoStreamInfo>()}, }}, {{ }}, }; -::uint8_t* SetVideoStreamingRequest::_InternalSerialize( +::uint8_t* SetVideoStreamInfoRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::video_streaming(this), - _Internal::video_streaming(this).GetCachedSize(), target, stream); + // repeated .mavsdk.rpc.camera_server.VideoStreamInfo video_stream_infos = 1; + for (unsigned i = 0, + n = static_cast(this->_internal_video_stream_infos_size()); i < n; i++) { + const auto& repfield = this->_internal_video_stream_infos().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(1, repfield, repfield.GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -2661,109 +2747,105 @@ ::uint8_t* SetVideoStreamingRequest::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) return target; } -::size_t SetVideoStreamingRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) +::size_t SetVideoStreamInfoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { + // repeated .mavsdk.rpc.camera_server.VideoStreamInfo video_stream_infos = 1; + total_size += 1UL * this->_internal_video_stream_infos_size(); + for (const auto& msg : this->_internal_video_stream_infos()) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.video_streaming_); + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); } - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetVideoStreamingRequest::_class_data_ = { - SetVideoStreamingRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetVideoStreamInfoRequest::_class_data_ = { + SetVideoStreamInfoRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetVideoStreamingRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetVideoStreamInfoRequest::GetClassData() const { return &_class_data_; } -void SetVideoStreamingRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) +void SetVideoStreamInfoRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_video_streaming()->::mavsdk::rpc::camera_server::VideoStreaming::MergeFrom( - from._internal_video_streaming()); - } + _this->_internal_mutable_video_stream_infos()->MergeFrom( + from._internal_video_stream_infos()); _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetVideoStreamingRequest::CopyFrom(const SetVideoStreamingRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) +void SetVideoStreamInfoRequest::CopyFrom(const SetVideoStreamInfoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetVideoStreamingRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetVideoStreamInfoRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetVideoStreamingRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetVideoStreamInfoRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetVideoStreamingRequest::InternalSwap(SetVideoStreamingRequest* PROTOBUF_RESTRICT other) { +void SetVideoStreamInfoRequest::InternalSwap(SetVideoStreamInfoRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.video_streaming_, other->_impl_.video_streaming_); + _impl_.video_stream_infos_.InternalSwap(&other->_impl_.video_stream_infos_); } -::google::protobuf::Metadata SetVideoStreamingRequest::GetMetadata() const { +::google::protobuf::Metadata SetVideoStreamInfoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[2]); } // =================================================================== -class SetVideoStreamingResponse::_Internal { +class SetVideoStreamInfoResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(SetVideoStreamingResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const SetVideoStreamingResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetVideoStreamInfoResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const SetVideoStreamInfoResponse* msg); static void set_has_camera_server_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera_server::CameraServerResult& SetVideoStreamingResponse::_Internal::camera_server_result(const SetVideoStreamingResponse* msg) { +const ::mavsdk::rpc::camera_server::CameraServerResult& SetVideoStreamInfoResponse::_Internal::camera_server_result(const SetVideoStreamInfoResponse* msg) { return *msg->_impl_.camera_server_result_; } -SetVideoStreamingResponse::SetVideoStreamingResponse(::google::protobuf::Arena* arena) +SetVideoStreamInfoResponse::SetVideoStreamInfoResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) } -inline PROTOBUF_NDEBUG_INLINE SetVideoStreamingResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetVideoStreamInfoResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetVideoStreamingResponse::SetVideoStreamingResponse( +SetVideoStreamInfoResponse::SetVideoStreamInfoResponse( ::google::protobuf::Arena* arena, - const SetVideoStreamingResponse& from) + const SetVideoStreamInfoResponse& from) : ::google::protobuf::Message(arena) { - SetVideoStreamingResponse* const _this = this; + SetVideoStreamInfoResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -2773,30 +2855,30 @@ SetVideoStreamingResponse::SetVideoStreamingResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(arena, *from._impl_.camera_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) } -inline PROTOBUF_NDEBUG_INLINE SetVideoStreamingResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetVideoStreamInfoResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetVideoStreamInfoResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_server_result_ = {}; } -SetVideoStreamingResponse::~SetVideoStreamingResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetVideoStreamingResponse) +SetVideoStreamInfoResponse::~SetVideoStreamInfoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetVideoStreamingResponse::SharedDtor() { +inline void SetVideoStreamInfoResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_server_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetVideoStreamingResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) +PROTOBUF_NOINLINE void SetVideoStreamInfoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -2811,7 +2893,7 @@ PROTOBUF_NOINLINE void SetVideoStreamingResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetVideoStreamingResponse::_InternalParse( +const char* SetVideoStreamInfoResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -2819,9 +2901,9 @@ const char* SetVideoStreamingResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetVideoStreamingResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetVideoStreamInfoResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetVideoStreamingResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetVideoStreamInfoResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -2830,17 +2912,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetVideoStreamingResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetVideoStreamingResponse_default_instance_._instance, + &_SetVideoStreamInfoResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetVideoStreamingResponse, _impl_.camera_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetVideoStreamInfoResponse, _impl_.camera_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - {PROTOBUF_FIELD_OFFSET(SetVideoStreamingResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetVideoStreamInfoResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::CameraServerResult>()}, @@ -2848,10 +2930,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetVideoStreamingResponse::_table_ = { }}, }; -::uint8_t* SetVideoStreamingResponse::_InternalSerialize( +::uint8_t* SetVideoStreamInfoResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -2868,12 +2950,12 @@ ::uint8_t* SetVideoStreamingResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) return target; } -::size_t SetVideoStreamingResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) +::size_t SetVideoStreamInfoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -2890,18 +2972,18 @@ ::size_t SetVideoStreamingResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetVideoStreamingResponse::_class_data_ = { - SetVideoStreamingResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetVideoStreamInfoResponse::_class_data_ = { + SetVideoStreamInfoResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetVideoStreamingResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetVideoStreamInfoResponse::GetClassData() const { return &_class_data_; } -void SetVideoStreamingResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) +void SetVideoStreamInfoResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -2913,28 +2995,28 @@ void SetVideoStreamingResponse::MergeImpl(::google::protobuf::Message& to_msg, c _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetVideoStreamingResponse::CopyFrom(const SetVideoStreamingResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) +void SetVideoStreamInfoResponse::CopyFrom(const SetVideoStreamInfoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetVideoStreamingResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetVideoStreamInfoResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetVideoStreamingResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetVideoStreamInfoResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetVideoStreamingResponse::InternalSwap(SetVideoStreamingResponse* PROTOBUF_RESTRICT other) { +void SetVideoStreamInfoResponse::InternalSwap(SetVideoStreamInfoResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); } -::google::protobuf::Metadata SetVideoStreamingResponse::GetMetadata() const { +::google::protobuf::Metadata SetVideoStreamInfoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[3]); @@ -9850,68 +9932,81 @@ ::google::protobuf::Metadata Information::GetMetadata() const { } // =================================================================== -class VideoStreaming::_Internal { +class VideoStreamSettings::_Internal { public: }; -VideoStreaming::VideoStreaming(::google::protobuf::Arena* arena) +VideoStreamSettings::VideoStreamSettings(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.VideoStreaming) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.VideoStreamSettings) } -inline PROTOBUF_NDEBUG_INLINE VideoStreaming::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE VideoStreamSettings::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) - : rtsp_uri_(arena, from.rtsp_uri_), + : uri_(arena, from.uri_), _cached_size_{0} {} -VideoStreaming::VideoStreaming( +VideoStreamSettings::VideoStreamSettings( ::google::protobuf::Arena* arena, - const VideoStreaming& from) + const VideoStreamSettings& from) : ::google::protobuf::Message(arena) { - VideoStreaming* const _this = this; + VideoStreamSettings* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - _impl_.has_rtsp_server_ = from._impl_.has_rtsp_server_; + ::memcpy(reinterpret_cast(&_impl_) + + offsetof(Impl_, frame_rate_hz_), + reinterpret_cast(&from._impl_) + + offsetof(Impl_, frame_rate_hz_), + offsetof(Impl_, horizontal_fov_deg_) - + offsetof(Impl_, frame_rate_hz_) + + sizeof(Impl_::horizontal_fov_deg_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.VideoStreaming) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.VideoStreamSettings) } -inline PROTOBUF_NDEBUG_INLINE VideoStreaming::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE VideoStreamSettings::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : rtsp_uri_(arena), + : uri_(arena), _cached_size_{0} {} -inline void VideoStreaming::SharedCtor(::_pb::Arena* arena) { +inline void VideoStreamSettings::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.has_rtsp_server_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, frame_rate_hz_), + 0, + offsetof(Impl_, horizontal_fov_deg_) - + offsetof(Impl_, frame_rate_hz_) + + sizeof(Impl_::horizontal_fov_deg_)); } -VideoStreaming::~VideoStreaming() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.VideoStreaming) +VideoStreamSettings::~VideoStreamSettings() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.VideoStreamSettings) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void VideoStreaming::SharedDtor() { +inline void VideoStreamSettings::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - _impl_.rtsp_uri_.Destroy(); + _impl_.uri_.Destroy(); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void VideoStreaming::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.VideoStreaming) +PROTOBUF_NOINLINE void VideoStreamSettings::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.VideoStreamSettings) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.rtsp_uri_.ClearToEmpty(); - _impl_.has_rtsp_server_ = false; + _impl_.uri_.ClearToEmpty(); + ::memset(&_impl_.frame_rate_hz_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.horizontal_fov_deg_) - + reinterpret_cast(&_impl_.frame_rate_hz_)) + sizeof(_impl_.horizontal_fov_deg_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* VideoStreaming::_InternalParse( +const char* VideoStreamSettings::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9919,64 +10014,140 @@ const char* VideoStreaming::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<1, 2, 0, 56, 2> VideoStreaming::_table_ = { +const ::_pbi::TcParseTable<3, 7, 0, 56, 2> VideoStreamSettings::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 2, 8, // max_field_number, fast_idx_mask + 7, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967292, // skipmap + 4294967168, // skipmap offsetof(decltype(_table_), field_entries), - 2, // num_field_entries + 7, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_VideoStreaming_default_instance_._instance, + &_VideoStreamSettings_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // string rtsp_uri = 2; + {::_pbi::TcParser::MiniParse, {}}, + // float frame_rate_hz = 1; + {::_pbi::TcParser::FastF32S1, + {13, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.frame_rate_hz_)}}, + // uint32 horizontal_resolution_pix = 2; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamSettings, _impl_.horizontal_resolution_pix_), 63>(), + {16, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.horizontal_resolution_pix_)}}, + // uint32 vertical_resolution_pix = 3; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamSettings, _impl_.vertical_resolution_pix_), 63>(), + {24, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.vertical_resolution_pix_)}}, + // uint32 bit_rate_b_s = 4; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamSettings, _impl_.bit_rate_b_s_), 63>(), + {32, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.bit_rate_b_s_)}}, + // uint32 rotation_deg = 5; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamSettings, _impl_.rotation_deg_), 63>(), + {40, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.rotation_deg_)}}, + // string uri = 6; {::_pbi::TcParser::FastUS1, - {18, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreaming, _impl_.rtsp_uri_)}}, - // bool has_rtsp_server = 1; - {::_pbi::TcParser::SingularVarintNoZag1(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreaming, _impl_.has_rtsp_server_)}}, + {50, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.uri_)}}, + // float horizontal_fov_deg = 7; + {::_pbi::TcParser::FastF32S1, + {61, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.horizontal_fov_deg_)}}, }}, {{ 65535, 65535 }}, {{ - // bool has_rtsp_server = 1; - {PROTOBUF_FIELD_OFFSET(VideoStreaming, _impl_.has_rtsp_server_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kBool)}, - // string rtsp_uri = 2; - {PROTOBUF_FIELD_OFFSET(VideoStreaming, _impl_.rtsp_uri_), 0, 0, + // float frame_rate_hz = 1; + {PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.frame_rate_hz_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // uint32 horizontal_resolution_pix = 2; + {PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.horizontal_resolution_pix_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // uint32 vertical_resolution_pix = 3; + {PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.vertical_resolution_pix_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // uint32 bit_rate_b_s = 4; + {PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.bit_rate_b_s_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // uint32 rotation_deg = 5; + {PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.rotation_deg_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // string uri = 6; + {PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.uri_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // float horizontal_fov_deg = 7; + {PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.horizontal_fov_deg_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, // no aux_entries {{ - "\47\0\10\0\0\0\0\0" - "mavsdk.rpc.camera_server.VideoStreaming" - "rtsp_uri" + "\54\0\0\0\0\0\3\0" + "mavsdk.rpc.camera_server.VideoStreamSettings" + "uri" }}, }; -::uint8_t* VideoStreaming::_InternalSerialize( +::uint8_t* VideoStreamSettings::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.VideoStreaming) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.VideoStreamSettings) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // bool has_rtsp_server = 1; - if (this->_internal_has_rtsp_server() != 0) { + // float frame_rate_hz = 1; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_frame_rate_hz = this->_internal_frame_rate_hz(); + ::uint32_t raw_frame_rate_hz; + memcpy(&raw_frame_rate_hz, &tmp_frame_rate_hz, sizeof(tmp_frame_rate_hz)); + if (raw_frame_rate_hz != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteBoolToArray( - 1, this->_internal_has_rtsp_server(), target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 1, this->_internal_frame_rate_hz(), target); + } + + // uint32 horizontal_resolution_pix = 2; + if (this->_internal_horizontal_resolution_pix() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 2, this->_internal_horizontal_resolution_pix(), target); + } + + // uint32 vertical_resolution_pix = 3; + if (this->_internal_vertical_resolution_pix() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 3, this->_internal_vertical_resolution_pix(), target); + } + + // uint32 bit_rate_b_s = 4; + if (this->_internal_bit_rate_b_s() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 4, this->_internal_bit_rate_b_s(), target); } - // string rtsp_uri = 2; - if (!this->_internal_rtsp_uri().empty()) { - const std::string& _s = this->_internal_rtsp_uri(); + // uint32 rotation_deg = 5; + if (this->_internal_rotation_deg() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 5, this->_internal_rotation_deg(), target); + } + + // string uri = 6; + if (!this->_internal_uri().empty()) { + const std::string& _s = this->_internal_uri(); ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri"); - target = stream->WriteStringMaybeAliased(2, _s, target); + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.VideoStreamSettings.uri"); + target = stream->WriteStringMaybeAliased(6, _s, target); + } + + // float horizontal_fov_deg = 7; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_horizontal_fov_deg = this->_internal_horizontal_fov_deg(); + ::uint32_t raw_horizontal_fov_deg; + memcpy(&raw_horizontal_fov_deg, &tmp_horizontal_fov_deg, sizeof(tmp_horizontal_fov_deg)); + if (raw_horizontal_fov_deg != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 7, this->_internal_horizontal_fov_deg(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -9984,87 +10155,449 @@ ::uint8_t* VideoStreaming::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.VideoStreaming) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.VideoStreamSettings) return target; } -::size_t VideoStreaming::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.VideoStreaming) +::size_t VideoStreamSettings::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.VideoStreamSettings) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // string rtsp_uri = 2; - if (!this->_internal_rtsp_uri().empty()) { + // string uri = 6; + if (!this->_internal_uri().empty()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( - this->_internal_rtsp_uri()); + this->_internal_uri()); } - // bool has_rtsp_server = 1; - if (this->_internal_has_rtsp_server() != 0) { - total_size += 2; + // float frame_rate_hz = 1; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_frame_rate_hz = this->_internal_frame_rate_hz(); + ::uint32_t raw_frame_rate_hz; + memcpy(&raw_frame_rate_hz, &tmp_frame_rate_hz, sizeof(tmp_frame_rate_hz)); + if (raw_frame_rate_hz != 0) { + total_size += 5; + } + + // uint32 horizontal_resolution_pix = 2; + if (this->_internal_horizontal_resolution_pix() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_horizontal_resolution_pix()); + } + + // uint32 vertical_resolution_pix = 3; + if (this->_internal_vertical_resolution_pix() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_vertical_resolution_pix()); + } + + // uint32 bit_rate_b_s = 4; + if (this->_internal_bit_rate_b_s() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_bit_rate_b_s()); + } + + // uint32 rotation_deg = 5; + if (this->_internal_rotation_deg() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_rotation_deg()); + } + + // float horizontal_fov_deg = 7; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_horizontal_fov_deg = this->_internal_horizontal_fov_deg(); + ::uint32_t raw_horizontal_fov_deg; + memcpy(&raw_horizontal_fov_deg, &tmp_horizontal_fov_deg, sizeof(tmp_horizontal_fov_deg)); + if (raw_horizontal_fov_deg != 0) { + total_size += 5; } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData VideoStreaming::_class_data_ = { - VideoStreaming::MergeImpl, +const ::google::protobuf::Message::ClassData VideoStreamSettings::_class_data_ = { + VideoStreamSettings::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* VideoStreaming::GetClassData() const { +const ::google::protobuf::Message::ClassData* VideoStreamSettings::GetClassData() const { return &_class_data_; } -void VideoStreaming::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.VideoStreaming) +void VideoStreamSettings::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.VideoStreamSettings) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (!from._internal_rtsp_uri().empty()) { - _this->_internal_set_rtsp_uri(from._internal_rtsp_uri()); + if (!from._internal_uri().empty()) { + _this->_internal_set_uri(from._internal_uri()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_frame_rate_hz = from._internal_frame_rate_hz(); + ::uint32_t raw_frame_rate_hz; + memcpy(&raw_frame_rate_hz, &tmp_frame_rate_hz, sizeof(tmp_frame_rate_hz)); + if (raw_frame_rate_hz != 0) { + _this->_internal_set_frame_rate_hz(from._internal_frame_rate_hz()); + } + if (from._internal_horizontal_resolution_pix() != 0) { + _this->_internal_set_horizontal_resolution_pix(from._internal_horizontal_resolution_pix()); + } + if (from._internal_vertical_resolution_pix() != 0) { + _this->_internal_set_vertical_resolution_pix(from._internal_vertical_resolution_pix()); } - if (from._internal_has_rtsp_server() != 0) { - _this->_internal_set_has_rtsp_server(from._internal_has_rtsp_server()); + if (from._internal_bit_rate_b_s() != 0) { + _this->_internal_set_bit_rate_b_s(from._internal_bit_rate_b_s()); + } + if (from._internal_rotation_deg() != 0) { + _this->_internal_set_rotation_deg(from._internal_rotation_deg()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_horizontal_fov_deg = from._internal_horizontal_fov_deg(); + ::uint32_t raw_horizontal_fov_deg; + memcpy(&raw_horizontal_fov_deg, &tmp_horizontal_fov_deg, sizeof(tmp_horizontal_fov_deg)); + if (raw_horizontal_fov_deg != 0) { + _this->_internal_set_horizontal_fov_deg(from._internal_horizontal_fov_deg()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void VideoStreaming::CopyFrom(const VideoStreaming& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.VideoStreaming) +void VideoStreamSettings::CopyFrom(const VideoStreamSettings& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.VideoStreamSettings) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool VideoStreaming::IsInitialized() const { +PROTOBUF_NOINLINE bool VideoStreamSettings::IsInitialized() const { return true; } -::_pbi::CachedSize* VideoStreaming::AccessCachedSize() const { +::_pbi::CachedSize* VideoStreamSettings::AccessCachedSize() const { return &_impl_._cached_size_; } -void VideoStreaming::InternalSwap(VideoStreaming* PROTOBUF_RESTRICT other) { +void VideoStreamSettings::InternalSwap(VideoStreamSettings* PROTOBUF_RESTRICT other) { using std::swap; auto* arena = GetArena(); ABSL_DCHECK_EQ(arena, other->GetArena()); _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.rtsp_uri_, &other->_impl_.rtsp_uri_, arena); - swap(_impl_.has_rtsp_server_, other->_impl_.has_rtsp_server_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.uri_, &other->_impl_.uri_, arena); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.horizontal_fov_deg_) + + sizeof(VideoStreamSettings::_impl_.horizontal_fov_deg_) + - PROTOBUF_FIELD_OFFSET(VideoStreamSettings, _impl_.frame_rate_hz_)>( + reinterpret_cast(&_impl_.frame_rate_hz_), + reinterpret_cast(&other->_impl_.frame_rate_hz_)); } -::google::protobuf::Metadata VideoStreaming::GetMetadata() const { +::google::protobuf::Metadata VideoStreamSettings::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[47]); } // =================================================================== +class VideoStreamInfo::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::VideoStreamSettings& settings(const VideoStreamInfo* msg); + static void set_has_settings(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::VideoStreamSettings& VideoStreamInfo::_Internal::settings(const VideoStreamInfo* msg) { + return *msg->_impl_.settings_; +} +VideoStreamInfo::VideoStreamInfo(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.VideoStreamInfo) +} +inline PROTOBUF_NDEBUG_INLINE VideoStreamInfo::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +VideoStreamInfo::VideoStreamInfo( + ::google::protobuf::Arena* arena, + const VideoStreamInfo& from) + : ::google::protobuf::Message(arena) { + VideoStreamInfo* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.settings_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera_server::VideoStreamSettings>(arena, *from._impl_.settings_) + : nullptr; + ::memcpy(reinterpret_cast(&_impl_) + + offsetof(Impl_, stream_id_), + reinterpret_cast(&from._impl_) + + offsetof(Impl_, stream_id_), + offsetof(Impl_, spectrum_) - + offsetof(Impl_, stream_id_) + + sizeof(Impl_::spectrum_)); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.VideoStreamInfo) +} +inline PROTOBUF_NDEBUG_INLINE VideoStreamInfo::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void VideoStreamInfo::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, settings_), + 0, + offsetof(Impl_, spectrum_) - + offsetof(Impl_, settings_) + + sizeof(Impl_::spectrum_)); +} +VideoStreamInfo::~VideoStreamInfo() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.VideoStreamInfo) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void VideoStreamInfo::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.settings_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void VideoStreamInfo::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.VideoStreamInfo) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.settings_ != nullptr); + _impl_.settings_->Clear(); + } + ::memset(&_impl_.stream_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.spectrum_) - + reinterpret_cast(&_impl_.stream_id_)) + sizeof(_impl_.spectrum_)); + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* VideoStreamInfo::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<2, 4, 1, 0, 2> VideoStreamInfo::_table_ = { + { + PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_._has_bits_), + 0, // no _extensions_ + 4, 24, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967280, // skipmap + offsetof(decltype(_table_), field_entries), + 4, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_VideoStreamInfo_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.spectrum_), 63>(), + {32, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_)}}, + // int32 stream_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.stream_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.stream_id_)}}, + // .mavsdk.rpc.camera_server.VideoStreamSettings settings = 2; + {::_pbi::TcParser::FastMtS1, + {18, 0, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_)}}, + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamStatus status = 3; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.status_), 63>(), + {24, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.status_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 stream_id = 1; + {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.stream_id_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.camera_server.VideoStreamSettings settings = 2; + {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamStatus status = 3; + {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.status_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; + {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::VideoStreamSettings>()}, + }}, {{ + }}, +}; + +::uint8_t* VideoStreamInfo::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.VideoStreamInfo) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_stream_id(), target); + } + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.VideoStreamSettings settings = 2; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 2, _Internal::settings(this), + _Internal::settings(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamStatus status = 3; + if (this->_internal_status() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 3, this->_internal_status(), target); + } + + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; + if (this->_internal_spectrum() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 4, this->_internal_spectrum(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.VideoStreamInfo) + return target; +} + +::size_t VideoStreamInfo::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.VideoStreamInfo) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.VideoStreamSettings settings = 2; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.settings_); + } + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamStatus status = 3; + if (this->_internal_status() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_status()); + } + + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; + if (this->_internal_spectrum() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_spectrum()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData VideoStreamInfo::_class_data_ = { + VideoStreamInfo::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* VideoStreamInfo::GetClassData() const { + return &_class_data_; +} + +void VideoStreamInfo::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.VideoStreamInfo) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_settings()->::mavsdk::rpc::camera_server::VideoStreamSettings::MergeFrom( + from._internal_settings()); + } + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } + if (from._internal_status() != 0) { + _this->_internal_set_status(from._internal_status()); + } + if (from._internal_spectrum() != 0) { + _this->_internal_set_spectrum(from._internal_spectrum()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void VideoStreamInfo::CopyFrom(const VideoStreamInfo& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.VideoStreamInfo) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool VideoStreamInfo::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* VideoStreamInfo::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void VideoStreamInfo::InternalSwap(VideoStreamInfo* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_) + + sizeof(VideoStreamInfo::_impl_.spectrum_) + - PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_)>( + reinterpret_cast(&_impl_.settings_), + reinterpret_cast(&other->_impl_.settings_)); +} + +::google::protobuf::Metadata VideoStreamInfo::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[48]); +} +// =================================================================== + class Position::_Internal { public: }; @@ -10365,7 +10898,7 @@ void Position::InternalSwap(Position* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[48]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[49]); } // =================================================================== @@ -10669,7 +11202,7 @@ void Quaternion::InternalSwap(Quaternion* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[49]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[50]); } // =================================================================== @@ -11042,7 +11575,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[50]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[51]); } // =================================================================== @@ -11258,7 +11791,7 @@ void CameraServerResult::InternalSwap(CameraServerResult* PROTOBUF_RESTRICT othe ::google::protobuf::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[51]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[52]); } // =================================================================== @@ -11664,7 +12197,7 @@ void StorageInformation::InternalSwap(StorageInformation* PROTOBUF_RESTRICT othe ::google::protobuf::Metadata StorageInformation::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[52]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[53]); } // =================================================================== @@ -12000,7 +12533,7 @@ void CaptureStatus::InternalSwap(CaptureStatus* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata CaptureStatus::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[53]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[54]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index 5aa2d79af1..f1ce4a445f 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -163,12 +163,12 @@ extern SetInformationResponseDefaultTypeInternal _SetInformationResponse_default class SetModeResponse; struct SetModeResponseDefaultTypeInternal; extern SetModeResponseDefaultTypeInternal _SetModeResponse_default_instance_; -class SetVideoStreamingRequest; -struct SetVideoStreamingRequestDefaultTypeInternal; -extern SetVideoStreamingRequestDefaultTypeInternal _SetVideoStreamingRequest_default_instance_; -class SetVideoStreamingResponse; -struct SetVideoStreamingResponseDefaultTypeInternal; -extern SetVideoStreamingResponseDefaultTypeInternal _SetVideoStreamingResponse_default_instance_; +class SetVideoStreamInfoRequest; +struct SetVideoStreamInfoRequestDefaultTypeInternal; +extern SetVideoStreamInfoRequestDefaultTypeInternal _SetVideoStreamInfoRequest_default_instance_; +class SetVideoStreamInfoResponse; +struct SetVideoStreamInfoResponseDefaultTypeInternal; +extern SetVideoStreamInfoResponseDefaultTypeInternal _SetVideoStreamInfoResponse_default_instance_; class StartVideoResponse; struct StartVideoResponseDefaultTypeInternal; extern StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; @@ -220,9 +220,12 @@ extern SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_d class TakePhotoResponse; struct TakePhotoResponseDefaultTypeInternal; extern TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; -class VideoStreaming; -struct VideoStreamingDefaultTypeInternal; -extern VideoStreamingDefaultTypeInternal _VideoStreaming_default_instance_; +class VideoStreamInfo; +struct VideoStreamInfoDefaultTypeInternal; +extern VideoStreamInfoDefaultTypeInternal _VideoStreamInfo_default_instance_; +class VideoStreamSettings; +struct VideoStreamSettingsDefaultTypeInternal; +extern VideoStreamSettingsDefaultTypeInternal _VideoStreamSettings_default_instance_; } // namespace camera_server } // namespace rpc } // namespace mavsdk @@ -234,6 +237,73 @@ namespace protobuf { namespace mavsdk { namespace rpc { namespace camera_server { +enum VideoStreamInfo_VideoStreamStatus : int { + VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_NOT_RUNNING = 0, + VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_IN_PROGRESS = 1, + VideoStreamInfo_VideoStreamStatus_VideoStreamInfo_VideoStreamStatus_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + VideoStreamInfo_VideoStreamStatus_VideoStreamInfo_VideoStreamStatus_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool VideoStreamInfo_VideoStreamStatus_IsValid(int value); +extern const uint32_t VideoStreamInfo_VideoStreamStatus_internal_data_[]; +constexpr VideoStreamInfo_VideoStreamStatus VideoStreamInfo_VideoStreamStatus_VideoStreamStatus_MIN = static_cast(0); +constexpr VideoStreamInfo_VideoStreamStatus VideoStreamInfo_VideoStreamStatus_VideoStreamStatus_MAX = static_cast(1); +constexpr int VideoStreamInfo_VideoStreamStatus_VideoStreamStatus_ARRAYSIZE = 1 + 1; +const ::google::protobuf::EnumDescriptor* +VideoStreamInfo_VideoStreamStatus_descriptor(); +template +const std::string& VideoStreamInfo_VideoStreamStatus_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to VideoStreamStatus_Name()."); + return VideoStreamInfo_VideoStreamStatus_Name(static_cast(value)); +} +template <> +inline const std::string& VideoStreamInfo_VideoStreamStatus_Name(VideoStreamInfo_VideoStreamStatus value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool VideoStreamInfo_VideoStreamStatus_Parse(absl::string_view name, VideoStreamInfo_VideoStreamStatus* value) { + return ::google::protobuf::internal::ParseNamedEnum( + VideoStreamInfo_VideoStreamStatus_descriptor(), name, value); +} +enum VideoStreamInfo_VideoStreamSpectrum : int { + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_UNKNOWN = 0, + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT = 1, + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_INFRARED = 2, + VideoStreamInfo_VideoStreamSpectrum_VideoStreamInfo_VideoStreamSpectrum_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + VideoStreamInfo_VideoStreamSpectrum_VideoStreamInfo_VideoStreamSpectrum_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool VideoStreamInfo_VideoStreamSpectrum_IsValid(int value); +extern const uint32_t VideoStreamInfo_VideoStreamSpectrum_internal_data_[]; +constexpr VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo_VideoStreamSpectrum_VideoStreamSpectrum_MIN = static_cast(0); +constexpr VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo_VideoStreamSpectrum_VideoStreamSpectrum_MAX = static_cast(2); +constexpr int VideoStreamInfo_VideoStreamSpectrum_VideoStreamSpectrum_ARRAYSIZE = 2 + 1; +const ::google::protobuf::EnumDescriptor* +VideoStreamInfo_VideoStreamSpectrum_descriptor(); +template +const std::string& VideoStreamInfo_VideoStreamSpectrum_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to VideoStreamSpectrum_Name()."); + return VideoStreamInfo_VideoStreamSpectrum_Name(static_cast(value)); +} +template <> +inline const std::string& VideoStreamInfo_VideoStreamSpectrum_Name(VideoStreamInfo_VideoStreamSpectrum value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool VideoStreamInfo_VideoStreamSpectrum_Parse(absl::string_view name, VideoStreamInfo_VideoStreamSpectrum* value) { + return ::google::protobuf::internal::ParseNamedEnum( + VideoStreamInfo_VideoStreamSpectrum_descriptor(), name, value); +} enum CameraServerResult_Result : int { CameraServerResult_Result_RESULT_UNKNOWN = 0, CameraServerResult_Result_RESULT_SUCCESS = 1, @@ -483,26 +553,26 @@ inline bool Mode_Parse(absl::string_view name, Mode* value) { // ------------------------------------------------------------------- -class VideoStreaming final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.VideoStreaming) */ { +class VideoStreamSettings final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.VideoStreamSettings) */ { public: - inline VideoStreaming() : VideoStreaming(nullptr) {} - ~VideoStreaming() override; + inline VideoStreamSettings() : VideoStreamSettings(nullptr) {} + ~VideoStreamSettings() override; template - explicit PROTOBUF_CONSTEXPR VideoStreaming(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR VideoStreamSettings(::google::protobuf::internal::ConstantInitialized); - inline VideoStreaming(const VideoStreaming& from) - : VideoStreaming(nullptr, from) {} - VideoStreaming(VideoStreaming&& from) noexcept - : VideoStreaming() { + inline VideoStreamSettings(const VideoStreamSettings& from) + : VideoStreamSettings(nullptr, from) {} + VideoStreamSettings(VideoStreamSettings&& from) noexcept + : VideoStreamSettings() { *this = ::std::move(from); } - inline VideoStreaming& operator=(const VideoStreaming& from) { + inline VideoStreamSettings& operator=(const VideoStreamSettings& from) { CopyFrom(from); return *this; } - inline VideoStreaming& operator=(VideoStreaming&& from) noexcept { + inline VideoStreamSettings& operator=(VideoStreamSettings&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -534,20 +604,20 @@ class VideoStreaming final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const VideoStreaming& default_instance() { + static const VideoStreamSettings& default_instance() { return *internal_default_instance(); } - static inline const VideoStreaming* internal_default_instance() { - return reinterpret_cast( - &_VideoStreaming_default_instance_); + static inline const VideoStreamSettings* internal_default_instance() { + return reinterpret_cast( + &_VideoStreamSettings_default_instance_); } static constexpr int kIndexInFileMessages = 47; - friend void swap(VideoStreaming& a, VideoStreaming& b) { + friend void swap(VideoStreamSettings& a, VideoStreamSettings& b) { a.Swap(&b); } - inline void Swap(VideoStreaming* other) { + inline void Swap(VideoStreamSettings* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -560,7 +630,7 @@ class VideoStreaming final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(VideoStreaming* other) { + void UnsafeArenaSwap(VideoStreamSettings* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -568,14 +638,14 @@ class VideoStreaming final : // implements Message ---------------------------------------------- - VideoStreaming* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + VideoStreamSettings* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const VideoStreaming& from); + void CopyFrom(const VideoStreamSettings& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const VideoStreaming& from) { - VideoStreaming::MergeImpl(*this, from); + void MergeFrom( const VideoStreamSettings& from) { + VideoStreamSettings::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -593,16 +663,16 @@ class VideoStreaming final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(VideoStreaming* other); + void InternalSwap(VideoStreamSettings* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.VideoStreaming"; + return "mavsdk.rpc.camera_server.VideoStreamSettings"; } protected: - explicit VideoStreaming(::google::protobuf::Arena* arena); - VideoStreaming(::google::protobuf::Arena* arena, const VideoStreaming& from); + explicit VideoStreamSettings(::google::protobuf::Arena* arena); + VideoStreamSettings(::google::protobuf::Arena* arena, const VideoStreamSettings& from); public: static const ClassData _class_data_; @@ -615,42 +685,97 @@ class VideoStreaming final : // accessors ------------------------------------------------------- enum : int { - kRtspUriFieldNumber = 2, - kHasRtspServerFieldNumber = 1, + kUriFieldNumber = 6, + kFrameRateHzFieldNumber = 1, + kHorizontalResolutionPixFieldNumber = 2, + kVerticalResolutionPixFieldNumber = 3, + kBitRateBSFieldNumber = 4, + kRotationDegFieldNumber = 5, + kHorizontalFovDegFieldNumber = 7, }; - // string rtsp_uri = 2; - void clear_rtsp_uri() ; - const std::string& rtsp_uri() const; + // string uri = 6; + void clear_uri() ; + const std::string& uri() const; template - void set_rtsp_uri(Arg_&& arg, Args_... args); - std::string* mutable_rtsp_uri(); - PROTOBUF_NODISCARD std::string* release_rtsp_uri(); - void set_allocated_rtsp_uri(std::string* value); + void set_uri(Arg_&& arg, Args_... args); + std::string* mutable_uri(); + PROTOBUF_NODISCARD std::string* release_uri(); + void set_allocated_uri(std::string* value); private: - const std::string& _internal_rtsp_uri() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_rtsp_uri( + const std::string& _internal_uri() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_uri( const std::string& value); - std::string* _internal_mutable_rtsp_uri(); + std::string* _internal_mutable_uri(); + + public: + // float frame_rate_hz = 1; + void clear_frame_rate_hz() ; + float frame_rate_hz() const; + void set_frame_rate_hz(float value); + + private: + float _internal_frame_rate_hz() const; + void _internal_set_frame_rate_hz(float value); public: - // bool has_rtsp_server = 1; - void clear_has_rtsp_server() ; - bool has_rtsp_server() const; - void set_has_rtsp_server(bool value); + // uint32 horizontal_resolution_pix = 2; + void clear_horizontal_resolution_pix() ; + ::uint32_t horizontal_resolution_pix() const; + void set_horizontal_resolution_pix(::uint32_t value); private: - bool _internal_has_rtsp_server() const; - void _internal_set_has_rtsp_server(bool value); + ::uint32_t _internal_horizontal_resolution_pix() const; + void _internal_set_horizontal_resolution_pix(::uint32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.VideoStreaming) + // uint32 vertical_resolution_pix = 3; + void clear_vertical_resolution_pix() ; + ::uint32_t vertical_resolution_pix() const; + void set_vertical_resolution_pix(::uint32_t value); + + private: + ::uint32_t _internal_vertical_resolution_pix() const; + void _internal_set_vertical_resolution_pix(::uint32_t value); + + public: + // uint32 bit_rate_b_s = 4; + void clear_bit_rate_b_s() ; + ::uint32_t bit_rate_b_s() const; + void set_bit_rate_b_s(::uint32_t value); + + private: + ::uint32_t _internal_bit_rate_b_s() const; + void _internal_set_bit_rate_b_s(::uint32_t value); + + public: + // uint32 rotation_deg = 5; + void clear_rotation_deg() ; + ::uint32_t rotation_deg() const; + void set_rotation_deg(::uint32_t value); + + private: + ::uint32_t _internal_rotation_deg() const; + void _internal_set_rotation_deg(::uint32_t value); + + public: + // float horizontal_fov_deg = 7; + void clear_horizontal_fov_deg() ; + float horizontal_fov_deg() const; + void set_horizontal_fov_deg(float value); + + private: + float _internal_horizontal_fov_deg() const; + void _internal_set_horizontal_fov_deg(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.VideoStreamSettings) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, + 3, 7, 0, 56, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -667,8 +792,13 @@ class VideoStreaming final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::ArenaStringPtr rtsp_uri_; - bool has_rtsp_server_; + ::google::protobuf::internal::ArenaStringPtr uri_; + float frame_rate_hz_; + ::uint32_t horizontal_resolution_pix_; + ::uint32_t vertical_resolution_pix_; + ::uint32_t bit_rate_b_s_; + ::uint32_t rotation_deg_; + float horizontal_fov_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -2445,7 +2575,7 @@ class StorageInformation final : &_StorageInformation_default_instance_); } static constexpr int kIndexInFileMessages = - 52; + 53; friend void swap(StorageInformation& a, StorageInformation& b) { a.Swap(&b); @@ -5200,7 +5330,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 49; + 50; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -5411,7 +5541,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 48; + 49; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -6291,7 +6421,7 @@ class CaptureStatus final : &_CaptureStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 53; + 54; friend void swap(CaptureStatus& a, CaptureStatus& b) { a.Swap(&b); @@ -6568,7 +6698,7 @@ class CameraServerResult final : &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 51; + 52; friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); @@ -6729,26 +6859,26 @@ class CameraServerResult final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SetVideoStreamingResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetVideoStreamingResponse) */ { +class VideoStreamInfo final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.VideoStreamInfo) */ { public: - inline SetVideoStreamingResponse() : SetVideoStreamingResponse(nullptr) {} - ~SetVideoStreamingResponse() override; + inline VideoStreamInfo() : VideoStreamInfo(nullptr) {} + ~VideoStreamInfo() override; template - explicit PROTOBUF_CONSTEXPR SetVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR VideoStreamInfo(::google::protobuf::internal::ConstantInitialized); - inline SetVideoStreamingResponse(const SetVideoStreamingResponse& from) - : SetVideoStreamingResponse(nullptr, from) {} - SetVideoStreamingResponse(SetVideoStreamingResponse&& from) noexcept - : SetVideoStreamingResponse() { + inline VideoStreamInfo(const VideoStreamInfo& from) + : VideoStreamInfo(nullptr, from) {} + VideoStreamInfo(VideoStreamInfo&& from) noexcept + : VideoStreamInfo() { *this = ::std::move(from); } - inline SetVideoStreamingResponse& operator=(const SetVideoStreamingResponse& from) { + inline VideoStreamInfo& operator=(const VideoStreamInfo& from) { CopyFrom(from); return *this; } - inline SetVideoStreamingResponse& operator=(SetVideoStreamingResponse&& from) noexcept { + inline VideoStreamInfo& operator=(VideoStreamInfo&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6780,20 +6910,20 @@ class SetVideoStreamingResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetVideoStreamingResponse& default_instance() { + static const VideoStreamInfo& default_instance() { return *internal_default_instance(); } - static inline const SetVideoStreamingResponse* internal_default_instance() { - return reinterpret_cast( - &_SetVideoStreamingResponse_default_instance_); + static inline const VideoStreamInfo* internal_default_instance() { + return reinterpret_cast( + &_VideoStreamInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 3; + 48; - friend void swap(SetVideoStreamingResponse& a, SetVideoStreamingResponse& b) { + friend void swap(VideoStreamInfo& a, VideoStreamInfo& b) { a.Swap(&b); } - inline void Swap(SetVideoStreamingResponse* other) { + inline void Swap(VideoStreamInfo* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6806,7 +6936,7 @@ class SetVideoStreamingResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetVideoStreamingResponse* other) { + void UnsafeArenaSwap(VideoStreamInfo* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6814,14 +6944,14 @@ class SetVideoStreamingResponse final : // implements Message ---------------------------------------------- - SetVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + VideoStreamInfo* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetVideoStreamingResponse& from); + void CopyFrom(const VideoStreamInfo& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetVideoStreamingResponse& from) { - SetVideoStreamingResponse::MergeImpl(*this, from); + void MergeFrom( const VideoStreamInfo& from) { + VideoStreamInfo::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -6839,16 +6969,16 @@ class SetVideoStreamingResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetVideoStreamingResponse* other); + void InternalSwap(VideoStreamInfo* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetVideoStreamingResponse"; + return "mavsdk.rpc.camera_server.VideoStreamInfo"; } protected: - explicit SetVideoStreamingResponse(::google::protobuf::Arena* arena); - SetVideoStreamingResponse(::google::protobuf::Arena* arena, const SetVideoStreamingResponse& from); + explicit VideoStreamInfo(::google::protobuf::Arena* arena); + VideoStreamInfo(::google::protobuf::Arena* arena, const VideoStreamInfo& from); public: static const ClassData _class_data_; @@ -6858,33 +6988,107 @@ class SetVideoStreamingResponse final : // nested types ---------------------------------------------------- + using VideoStreamStatus = VideoStreamInfo_VideoStreamStatus; + static constexpr VideoStreamStatus VIDEO_STREAM_STATUS_NOT_RUNNING = VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_NOT_RUNNING; + static constexpr VideoStreamStatus VIDEO_STREAM_STATUS_IN_PROGRESS = VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_IN_PROGRESS; + static inline bool VideoStreamStatus_IsValid(int value) { + return VideoStreamInfo_VideoStreamStatus_IsValid(value); + } + static constexpr VideoStreamStatus VideoStreamStatus_MIN = VideoStreamInfo_VideoStreamStatus_VideoStreamStatus_MIN; + static constexpr VideoStreamStatus VideoStreamStatus_MAX = VideoStreamInfo_VideoStreamStatus_VideoStreamStatus_MAX; + static constexpr int VideoStreamStatus_ARRAYSIZE = VideoStreamInfo_VideoStreamStatus_VideoStreamStatus_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* VideoStreamStatus_descriptor() { + return VideoStreamInfo_VideoStreamStatus_descriptor(); + } + template + static inline const std::string& VideoStreamStatus_Name(T value) { + return VideoStreamInfo_VideoStreamStatus_Name(value); + } + static inline bool VideoStreamStatus_Parse(absl::string_view name, VideoStreamStatus* value) { + return VideoStreamInfo_VideoStreamStatus_Parse(name, value); + } + + using VideoStreamSpectrum = VideoStreamInfo_VideoStreamSpectrum; + static constexpr VideoStreamSpectrum VIDEO_STREAM_SPECTRUM_UNKNOWN = VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_UNKNOWN; + static constexpr VideoStreamSpectrum VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT = VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT; + static constexpr VideoStreamSpectrum VIDEO_STREAM_SPECTRUM_INFRARED = VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_INFRARED; + static inline bool VideoStreamSpectrum_IsValid(int value) { + return VideoStreamInfo_VideoStreamSpectrum_IsValid(value); + } + static constexpr VideoStreamSpectrum VideoStreamSpectrum_MIN = VideoStreamInfo_VideoStreamSpectrum_VideoStreamSpectrum_MIN; + static constexpr VideoStreamSpectrum VideoStreamSpectrum_MAX = VideoStreamInfo_VideoStreamSpectrum_VideoStreamSpectrum_MAX; + static constexpr int VideoStreamSpectrum_ARRAYSIZE = VideoStreamInfo_VideoStreamSpectrum_VideoStreamSpectrum_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* VideoStreamSpectrum_descriptor() { + return VideoStreamInfo_VideoStreamSpectrum_descriptor(); + } + template + static inline const std::string& VideoStreamSpectrum_Name(T value) { + return VideoStreamInfo_VideoStreamSpectrum_Name(value); + } + static inline bool VideoStreamSpectrum_Parse(absl::string_view name, VideoStreamSpectrum* value) { + return VideoStreamInfo_VideoStreamSpectrum_Parse(name, value); + } + // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kSettingsFieldNumber = 2, + kStreamIdFieldNumber = 1, + kStatusFieldNumber = 3, + kSpectrumFieldNumber = 4, }; - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - bool has_camera_server_result() const; - void clear_camera_server_result() ; - const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); - ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); - void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value); - void unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value); - ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // .mavsdk.rpc.camera_server.VideoStreamSettings settings = 2; + bool has_settings() const; + void clear_settings() ; + const ::mavsdk::rpc::camera_server::VideoStreamSettings& settings() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::VideoStreamSettings* release_settings(); + ::mavsdk::rpc::camera_server::VideoStreamSettings* mutable_settings(); + void set_allocated_settings(::mavsdk::rpc::camera_server::VideoStreamSettings* value); + void unsafe_arena_set_allocated_settings(::mavsdk::rpc::camera_server::VideoStreamSettings* value); + ::mavsdk::rpc::camera_server::VideoStreamSettings* unsafe_arena_release_settings(); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + const ::mavsdk::rpc::camera_server::VideoStreamSettings& _internal_settings() const; + ::mavsdk::rpc::camera_server::VideoStreamSettings* _internal_mutable_settings(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamStatus status = 3; + void clear_status() ; + ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus status() const; + void set_status(::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus value); + + private: + ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus _internal_status() const; + void _internal_set_status(::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus value); + + public: + // .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; + void clear_spectrum() ; + ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum spectrum() const; + void set_spectrum(::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum value); + + private: + ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum _internal_spectrum() const; + void _internal_set_spectrum(::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.VideoStreamInfo) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 2, 4, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -6903,33 +7107,36 @@ class SetVideoStreamingResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + ::mavsdk::rpc::camera_server::VideoStreamSettings* settings_; + ::int32_t stream_id_; + int status_; + int spectrum_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SetVideoStreamingRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetVideoStreamingRequest) */ { +class SetVideoStreamInfoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) */ { public: - inline SetVideoStreamingRequest() : SetVideoStreamingRequest(nullptr) {} - ~SetVideoStreamingRequest() override; + inline SetVideoStreamInfoResponse() : SetVideoStreamInfoResponse(nullptr) {} + ~SetVideoStreamInfoResponse() override; template - explicit PROTOBUF_CONSTEXPR SetVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetVideoStreamInfoResponse(::google::protobuf::internal::ConstantInitialized); - inline SetVideoStreamingRequest(const SetVideoStreamingRequest& from) - : SetVideoStreamingRequest(nullptr, from) {} - SetVideoStreamingRequest(SetVideoStreamingRequest&& from) noexcept - : SetVideoStreamingRequest() { + inline SetVideoStreamInfoResponse(const SetVideoStreamInfoResponse& from) + : SetVideoStreamInfoResponse(nullptr, from) {} + SetVideoStreamInfoResponse(SetVideoStreamInfoResponse&& from) noexcept + : SetVideoStreamInfoResponse() { *this = ::std::move(from); } - inline SetVideoStreamingRequest& operator=(const SetVideoStreamingRequest& from) { + inline SetVideoStreamInfoResponse& operator=(const SetVideoStreamInfoResponse& from) { CopyFrom(from); return *this; } - inline SetVideoStreamingRequest& operator=(SetVideoStreamingRequest&& from) noexcept { + inline SetVideoStreamInfoResponse& operator=(SetVideoStreamInfoResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6961,20 +7168,20 @@ class SetVideoStreamingRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetVideoStreamingRequest& default_instance() { + static const SetVideoStreamInfoResponse& default_instance() { return *internal_default_instance(); } - static inline const SetVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_SetVideoStreamingRequest_default_instance_); + static inline const SetVideoStreamInfoResponse* internal_default_instance() { + return reinterpret_cast( + &_SetVideoStreamInfoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 2; + 3; - friend void swap(SetVideoStreamingRequest& a, SetVideoStreamingRequest& b) { + friend void swap(SetVideoStreamInfoResponse& a, SetVideoStreamInfoResponse& b) { a.Swap(&b); } - inline void Swap(SetVideoStreamingRequest* other) { + inline void Swap(SetVideoStreamInfoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6987,7 +7194,7 @@ class SetVideoStreamingRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetVideoStreamingRequest* other) { + void UnsafeArenaSwap(SetVideoStreamInfoResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6995,14 +7202,14 @@ class SetVideoStreamingRequest final : // implements Message ---------------------------------------------- - SetVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetVideoStreamInfoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetVideoStreamingRequest& from); + void CopyFrom(const SetVideoStreamInfoResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetVideoStreamingRequest& from) { - SetVideoStreamingRequest::MergeImpl(*this, from); + void MergeFrom( const SetVideoStreamInfoResponse& from) { + SetVideoStreamInfoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7020,16 +7227,16 @@ class SetVideoStreamingRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetVideoStreamingRequest* other); + void InternalSwap(SetVideoStreamInfoResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetVideoStreamingRequest"; + return "mavsdk.rpc.camera_server.SetVideoStreamInfoResponse"; } protected: - explicit SetVideoStreamingRequest(::google::protobuf::Arena* arena); - SetVideoStreamingRequest(::google::protobuf::Arena* arena, const SetVideoStreamingRequest& from); + explicit SetVideoStreamInfoResponse(::google::protobuf::Arena* arena); + SetVideoStreamInfoResponse(::google::protobuf::Arena* arena, const SetVideoStreamInfoResponse& from); public: static const ClassData _class_data_; @@ -7042,24 +7249,24 @@ class SetVideoStreamingRequest final : // accessors ------------------------------------------------------- enum : int { - kVideoStreamingFieldNumber = 1, + kCameraServerResultFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; - bool has_video_streaming() const; - void clear_video_streaming() ; - const ::mavsdk::rpc::camera_server::VideoStreaming& video_streaming() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::VideoStreaming* release_video_streaming(); - ::mavsdk::rpc::camera_server::VideoStreaming* mutable_video_streaming(); - void set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* value); - void unsafe_arena_set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* value); - ::mavsdk::rpc::camera_server::VideoStreaming* unsafe_arena_release_video_streaming(); + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value); + void unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); private: - const ::mavsdk::rpc::camera_server::VideoStreaming& _internal_video_streaming() const; - ::mavsdk::rpc::camera_server::VideoStreaming* _internal_mutable_video_streaming(); + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse) private: class _Internal; @@ -7084,7 +7291,7 @@ class SetVideoStreamingRequest final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::VideoStreaming* video_streaming_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -9889,7 +10096,7 @@ class CaptureInfo final : &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 50; + 51; friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); @@ -10082,6 +10289,189 @@ class CaptureInfo final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- +class SetVideoStreamInfoRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) */ { + public: + inline SetVideoStreamInfoRequest() : SetVideoStreamInfoRequest(nullptr) {} + ~SetVideoStreamInfoRequest() override; + template + explicit PROTOBUF_CONSTEXPR SetVideoStreamInfoRequest(::google::protobuf::internal::ConstantInitialized); + + inline SetVideoStreamInfoRequest(const SetVideoStreamInfoRequest& from) + : SetVideoStreamInfoRequest(nullptr, from) {} + SetVideoStreamInfoRequest(SetVideoStreamInfoRequest&& from) noexcept + : SetVideoStreamInfoRequest() { + *this = ::std::move(from); + } + + inline SetVideoStreamInfoRequest& operator=(const SetVideoStreamInfoRequest& from) { + CopyFrom(from); + return *this; + } + inline SetVideoStreamInfoRequest& operator=(SetVideoStreamInfoRequest&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetVideoStreamInfoRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetVideoStreamInfoRequest* internal_default_instance() { + return reinterpret_cast( + &_SetVideoStreamInfoRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(SetVideoStreamInfoRequest& a, SetVideoStreamInfoRequest& b) { + a.Swap(&b); + } + inline void Swap(SetVideoStreamInfoRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetVideoStreamInfoRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetVideoStreamInfoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const SetVideoStreamInfoRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const SetVideoStreamInfoRequest& from) { + SetVideoStreamInfoRequest::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(SetVideoStreamInfoRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SetVideoStreamInfoRequest"; + } + protected: + explicit SetVideoStreamInfoRequest(::google::protobuf::Arena* arena); + SetVideoStreamInfoRequest(::google::protobuf::Arena* arena, const SetVideoStreamInfoRequest& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kVideoStreamInfosFieldNumber = 1, + }; + // repeated .mavsdk.rpc.camera_server.VideoStreamInfo video_stream_infos = 1; + int video_stream_infos_size() const; + private: + int _internal_video_stream_infos_size() const; + + public: + void clear_video_stream_infos() ; + ::mavsdk::rpc::camera_server::VideoStreamInfo* mutable_video_stream_infos(int index); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::camera_server::VideoStreamInfo >* + mutable_video_stream_infos(); + private: + const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera_server::VideoStreamInfo>& _internal_video_stream_infos() const; + ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera_server::VideoStreamInfo>* _internal_mutable_video_stream_infos(); + public: + const ::mavsdk::rpc::camera_server::VideoStreamInfo& video_stream_infos(int index) const; + ::mavsdk::rpc::camera_server::VideoStreamInfo* add_video_stream_infos(); + const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::camera_server::VideoStreamInfo >& + video_stream_infos() const; + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::camera_server::VideoStreamInfo > video_stream_infos_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + class RespondTakePhotoRequest final : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { public: @@ -10489,129 +10879,82 @@ inline void SetInformationResponse::set_allocated_camera_server_result(::mavsdk: // ------------------------------------------------------------------- -// SetVideoStreamingRequest +// SetVideoStreamInfoRequest -// .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; -inline bool SetVideoStreamingRequest::has_video_streaming() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.video_streaming_ != nullptr); - return value; +// repeated .mavsdk.rpc.camera_server.VideoStreamInfo video_stream_infos = 1; +inline int SetVideoStreamInfoRequest::_internal_video_stream_infos_size() const { + return _internal_video_stream_infos().size(); } -inline void SetVideoStreamingRequest::clear_video_streaming() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.video_streaming_ != nullptr) _impl_.video_streaming_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; +inline int SetVideoStreamInfoRequest::video_stream_infos_size() const { + return _internal_video_stream_infos_size(); } -inline const ::mavsdk::rpc::camera_server::VideoStreaming& SetVideoStreamingRequest::_internal_video_streaming() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::camera_server::VideoStreaming* p = _impl_.video_streaming_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_VideoStreaming_default_instance_); +inline void SetVideoStreamInfoRequest::clear_video_stream_infos() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.video_stream_infos_.Clear(); } -inline const ::mavsdk::rpc::camera_server::VideoStreaming& SetVideoStreamingRequest::video_streaming() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) - return _internal_video_streaming(); +inline ::mavsdk::rpc::camera_server::VideoStreamInfo* SetVideoStreamInfoRequest::mutable_video_stream_infos(int index) + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest.video_stream_infos) + return _internal_mutable_video_stream_infos()->Mutable(index); } -inline void SetVideoStreamingRequest::unsafe_arena_set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* value) { +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera_server::VideoStreamInfo>* SetVideoStreamInfoRequest::mutable_video_stream_infos() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest.video_stream_infos) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.video_streaming_); - } - _impl_.video_streaming_ = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreaming*>(value); - if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) + return _internal_mutable_video_stream_infos(); } -inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::release_video_streaming() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::VideoStreaming* released = _impl_.video_streaming_; - _impl_.video_streaming_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - if (GetArena() == nullptr) { - delete old; - } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArena() != nullptr) { - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return released; +inline const ::mavsdk::rpc::camera_server::VideoStreamInfo& SetVideoStreamInfoRequest::video_stream_infos(int index) const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest.video_stream_infos) + return _internal_video_stream_infos().Get(index); } -inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::unsafe_arena_release_video_streaming() { +inline ::mavsdk::rpc::camera_server::VideoStreamInfo* SetVideoStreamInfoRequest::add_video_stream_infos() ABSL_ATTRIBUTE_LIFETIME_BOUND { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::VideoStreaming* temp = _impl_.video_streaming_; - _impl_.video_streaming_ = nullptr; - return temp; + ::mavsdk::rpc::camera_server::VideoStreamInfo* _add = _internal_mutable_video_stream_infos()->Add(); + // @@protoc_insertion_point(field_add:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest.video_stream_infos) + return _add; } -inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::_internal_mutable_video_streaming() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.video_streaming_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::VideoStreaming>(GetArena()); - _impl_.video_streaming_ = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreaming*>(p); - } - return _impl_.video_streaming_; +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera_server::VideoStreamInfo>& SetVideoStreamInfoRequest::video_stream_infos() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.camera_server.SetVideoStreamInfoRequest.video_stream_infos) + return _internal_video_stream_infos(); } -inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::mutable_video_streaming() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::camera_server::VideoStreaming* _msg = _internal_mutable_video_streaming(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) - return _msg; +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera_server::VideoStreamInfo>& +SetVideoStreamInfoRequest::_internal_video_stream_infos() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.video_stream_infos_; } -inline void SetVideoStreamingRequest::set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreaming*>(_impl_.video_streaming_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreaming*>(value)->GetArena(); - if (message_arena != submessage_arena) { - value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); - } - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - - _impl_.video_streaming_ = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreaming*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::camera_server::VideoStreamInfo>* +SetVideoStreamInfoRequest::_internal_mutable_video_stream_infos() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.video_stream_infos_; } // ------------------------------------------------------------------- -// SetVideoStreamingResponse +// SetVideoStreamInfoResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool SetVideoStreamingResponse::has_camera_server_result() const { +inline bool SetVideoStreamInfoResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void SetVideoStreamingResponse::clear_camera_server_result() { +inline void SetVideoStreamInfoResponse::clear_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetVideoStreamingResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetVideoStreamInfoResponse::_internal_camera_server_result() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetVideoStreamingResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetVideoStreamInfoResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse.camera_server_result) return _internal_camera_server_result(); } -inline void SetVideoStreamingResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void SetVideoStreamInfoResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.camera_server_result_); @@ -10622,9 +10965,9 @@ inline void SetVideoStreamingResponse::unsafe_arena_set_allocated_camera_server_ } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamInfoResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -10643,16 +10986,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingRespon #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamInfoResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamInfoResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -10661,12 +11004,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingRespon } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamInfoResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse.camera_server_result) return _msg; } -inline void SetVideoStreamingResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void SetVideoStreamInfoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { @@ -10684,7 +11027,7 @@ inline void SetVideoStreamingResponse::set_allocated_camera_server_result(::mavs } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamInfoResponse.camera_server_result) } // ------------------------------------------------------------------- @@ -13061,82 +13404,366 @@ inline void Information::set_allocated_definition_file_uri(std::string* value) { // ------------------------------------------------------------------- -// VideoStreaming +// VideoStreamSettings + +// float frame_rate_hz = 1; +inline void VideoStreamSettings::clear_frame_rate_hz() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.frame_rate_hz_ = 0; +} +inline float VideoStreamSettings::frame_rate_hz() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamSettings.frame_rate_hz) + return _internal_frame_rate_hz(); +} +inline void VideoStreamSettings::set_frame_rate_hz(float value) { + _internal_set_frame_rate_hz(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamSettings.frame_rate_hz) +} +inline float VideoStreamSettings::_internal_frame_rate_hz() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.frame_rate_hz_; +} +inline void VideoStreamSettings::_internal_set_frame_rate_hz(float value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.frame_rate_hz_ = value; +} + +// uint32 horizontal_resolution_pix = 2; +inline void VideoStreamSettings::clear_horizontal_resolution_pix() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.horizontal_resolution_pix_ = 0u; +} +inline ::uint32_t VideoStreamSettings::horizontal_resolution_pix() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamSettings.horizontal_resolution_pix) + return _internal_horizontal_resolution_pix(); +} +inline void VideoStreamSettings::set_horizontal_resolution_pix(::uint32_t value) { + _internal_set_horizontal_resolution_pix(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamSettings.horizontal_resolution_pix) +} +inline ::uint32_t VideoStreamSettings::_internal_horizontal_resolution_pix() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.horizontal_resolution_pix_; +} +inline void VideoStreamSettings::_internal_set_horizontal_resolution_pix(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.horizontal_resolution_pix_ = value; +} + +// uint32 vertical_resolution_pix = 3; +inline void VideoStreamSettings::clear_vertical_resolution_pix() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.vertical_resolution_pix_ = 0u; +} +inline ::uint32_t VideoStreamSettings::vertical_resolution_pix() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamSettings.vertical_resolution_pix) + return _internal_vertical_resolution_pix(); +} +inline void VideoStreamSettings::set_vertical_resolution_pix(::uint32_t value) { + _internal_set_vertical_resolution_pix(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamSettings.vertical_resolution_pix) +} +inline ::uint32_t VideoStreamSettings::_internal_vertical_resolution_pix() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.vertical_resolution_pix_; +} +inline void VideoStreamSettings::_internal_set_vertical_resolution_pix(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.vertical_resolution_pix_ = value; +} + +// uint32 bit_rate_b_s = 4; +inline void VideoStreamSettings::clear_bit_rate_b_s() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.bit_rate_b_s_ = 0u; +} +inline ::uint32_t VideoStreamSettings::bit_rate_b_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamSettings.bit_rate_b_s) + return _internal_bit_rate_b_s(); +} +inline void VideoStreamSettings::set_bit_rate_b_s(::uint32_t value) { + _internal_set_bit_rate_b_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamSettings.bit_rate_b_s) +} +inline ::uint32_t VideoStreamSettings::_internal_bit_rate_b_s() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.bit_rate_b_s_; +} +inline void VideoStreamSettings::_internal_set_bit_rate_b_s(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.bit_rate_b_s_ = value; +} -// bool has_rtsp_server = 1; -inline void VideoStreaming::clear_has_rtsp_server() { +// uint32 rotation_deg = 5; +inline void VideoStreamSettings::clear_rotation_deg() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.has_rtsp_server_ = false; + _impl_.rotation_deg_ = 0u; } -inline bool VideoStreaming::has_rtsp_server() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreaming.has_rtsp_server) - return _internal_has_rtsp_server(); +inline ::uint32_t VideoStreamSettings::rotation_deg() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamSettings.rotation_deg) + return _internal_rotation_deg(); } -inline void VideoStreaming::set_has_rtsp_server(bool value) { - _internal_set_has_rtsp_server(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreaming.has_rtsp_server) +inline void VideoStreamSettings::set_rotation_deg(::uint32_t value) { + _internal_set_rotation_deg(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamSettings.rotation_deg) } -inline bool VideoStreaming::_internal_has_rtsp_server() const { +inline ::uint32_t VideoStreamSettings::_internal_rotation_deg() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.has_rtsp_server_; + return _impl_.rotation_deg_; } -inline void VideoStreaming::_internal_set_has_rtsp_server(bool value) { +inline void VideoStreamSettings::_internal_set_rotation_deg(::uint32_t value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.has_rtsp_server_ = value; + _impl_.rotation_deg_ = value; } -// string rtsp_uri = 2; -inline void VideoStreaming::clear_rtsp_uri() { +// string uri = 6; +inline void VideoStreamSettings::clear_uri() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.rtsp_uri_.ClearToEmpty(); + _impl_.uri_.ClearToEmpty(); } -inline const std::string& VideoStreaming::rtsp_uri() const +inline const std::string& VideoStreamSettings::uri() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) - return _internal_rtsp_uri(); + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamSettings.uri) + return _internal_uri(); } template -inline PROTOBUF_ALWAYS_INLINE void VideoStreaming::set_rtsp_uri(Arg_&& arg, +inline PROTOBUF_ALWAYS_INLINE void VideoStreamSettings::set_uri(Arg_&& arg, Args_... args) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.rtsp_uri_.Set(static_cast(arg), args..., GetArena()); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) + _impl_.uri_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamSettings.uri) } -inline std::string* VideoStreaming::mutable_rtsp_uri() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_rtsp_uri(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) +inline std::string* VideoStreamSettings::mutable_uri() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_uri(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.VideoStreamSettings.uri) return _s; } -inline const std::string& VideoStreaming::_internal_rtsp_uri() const { +inline const std::string& VideoStreamSettings::_internal_uri() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.rtsp_uri_.Get(); + return _impl_.uri_.Get(); } -inline void VideoStreaming::_internal_set_rtsp_uri(const std::string& value) { +inline void VideoStreamSettings::_internal_set_uri(const std::string& value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.rtsp_uri_.Set(value, GetArena()); + _impl_.uri_.Set(value, GetArena()); } -inline std::string* VideoStreaming::_internal_mutable_rtsp_uri() { +inline std::string* VideoStreamSettings::_internal_mutable_uri() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - return _impl_.rtsp_uri_.Mutable( GetArena()); + return _impl_.uri_.Mutable( GetArena()); } -inline std::string* VideoStreaming::release_rtsp_uri() { +inline std::string* VideoStreamSettings::release_uri() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) - return _impl_.rtsp_uri_.Release(); + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.VideoStreamSettings.uri) + return _impl_.uri_.Release(); } -inline void VideoStreaming::set_allocated_rtsp_uri(std::string* value) { +inline void VideoStreamSettings::set_allocated_uri(std::string* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.rtsp_uri_.SetAllocated(value, GetArena()); + _impl_.uri_.SetAllocated(value, GetArena()); #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (_impl_.rtsp_uri_.IsDefault()) { - _impl_.rtsp_uri_.Set("", GetArena()); + if (_impl_.uri_.IsDefault()) { + _impl_.uri_.Set("", GetArena()); } #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.VideoStreamSettings.uri) +} + +// float horizontal_fov_deg = 7; +inline void VideoStreamSettings::clear_horizontal_fov_deg() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.horizontal_fov_deg_ = 0; +} +inline float VideoStreamSettings::horizontal_fov_deg() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamSettings.horizontal_fov_deg) + return _internal_horizontal_fov_deg(); +} +inline void VideoStreamSettings::set_horizontal_fov_deg(float value) { + _internal_set_horizontal_fov_deg(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamSettings.horizontal_fov_deg) +} +inline float VideoStreamSettings::_internal_horizontal_fov_deg() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.horizontal_fov_deg_; +} +inline void VideoStreamSettings::_internal_set_horizontal_fov_deg(float value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.horizontal_fov_deg_ = value; +} + +// ------------------------------------------------------------------- + +// VideoStreamInfo + +// int32 stream_id = 1; +inline void VideoStreamInfo::clear_stream_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.stream_id_ = 0; +} +inline ::int32_t VideoStreamInfo::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamInfo.stream_id) + return _internal_stream_id(); +} +inline void VideoStreamInfo::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamInfo.stream_id) +} +inline ::int32_t VideoStreamInfo::_internal_stream_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.stream_id_; +} +inline void VideoStreamInfo::_internal_set_stream_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.stream_id_ = value; +} + +// .mavsdk.rpc.camera_server.VideoStreamSettings settings = 2; +inline bool VideoStreamInfo::has_settings() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.settings_ != nullptr); + return value; +} +inline void VideoStreamInfo::clear_settings() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.settings_ != nullptr) _impl_.settings_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::VideoStreamSettings& VideoStreamInfo::_internal_settings() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::camera_server::VideoStreamSettings* p = _impl_.settings_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_VideoStreamSettings_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::VideoStreamSettings& VideoStreamInfo::settings() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamInfo.settings) + return _internal_settings(); +} +inline void VideoStreamInfo::unsafe_arena_set_allocated_settings(::mavsdk::rpc::camera_server::VideoStreamSettings* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.settings_); + } + _impl_.settings_ = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreamSettings*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.VideoStreamInfo.settings) +} +inline ::mavsdk::rpc::camera_server::VideoStreamSettings* VideoStreamInfo::release_settings() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::VideoStreamSettings* released = _impl_.settings_; + _impl_.settings_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::camera_server::VideoStreamSettings* VideoStreamInfo::unsafe_arena_release_settings() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.VideoStreamInfo.settings) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::VideoStreamSettings* temp = _impl_.settings_; + _impl_.settings_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::VideoStreamSettings* VideoStreamInfo::_internal_mutable_settings() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.settings_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::VideoStreamSettings>(GetArena()); + _impl_.settings_ = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreamSettings*>(p); + } + return _impl_.settings_; +} +inline ::mavsdk::rpc::camera_server::VideoStreamSettings* VideoStreamInfo::mutable_settings() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::camera_server::VideoStreamSettings* _msg = _internal_mutable_settings(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.VideoStreamInfo.settings) + return _msg; +} +inline void VideoStreamInfo::set_allocated_settings(::mavsdk::rpc::camera_server::VideoStreamSettings* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreamSettings*>(_impl_.settings_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreamSettings*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.settings_ = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreamSettings*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.VideoStreamInfo.settings) +} + +// .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamStatus status = 3; +inline void VideoStreamInfo::clear_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.status_ = 0; +} +inline ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus VideoStreamInfo::status() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamInfo.status) + return _internal_status(); +} +inline void VideoStreamInfo::set_status(::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus value) { + _internal_set_status(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamInfo.status) +} +inline ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus VideoStreamInfo::_internal_status() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus>(_impl_.status_); +} +inline void VideoStreamInfo::_internal_set_status(::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.status_ = value; +} + +// .mavsdk.rpc.camera_server.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; +inline void VideoStreamInfo::clear_spectrum() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.spectrum_ = 0; +} +inline ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo::spectrum() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreamInfo.spectrum) + return _internal_spectrum(); +} +inline void VideoStreamInfo::set_spectrum(::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum value) { + _internal_set_spectrum(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreamInfo.spectrum) +} +inline ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum VideoStreamInfo::_internal_spectrum() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum>(_impl_.spectrum_); +} +inline void VideoStreamInfo::_internal_set_spectrum(::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.spectrum_ = value; } // ------------------------------------------------------------------- @@ -14072,6 +14699,18 @@ inline void CaptureStatus::_internal_set_image_count(::int32_t value) { namespace google { namespace protobuf { +template <> +struct is_proto_enum<::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus>() { + return ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus_descriptor(); +} +template <> +struct is_proto_enum<::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum>() { + return ::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamSpectrum_descriptor(); +} template <> struct is_proto_enum<::mavsdk::rpc::camera_server::CameraServerResult_Result> : std::true_type {}; template <> diff --git a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h index 1317804d64..61507398b0 100644 --- a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h @@ -415,6 +415,8 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { { auto rpc_obj = std::make_unique(); + rpc_obj->set_stream_id(video_stream_info.stream_id); + rpc_obj->set_allocated_settings( translateToRpcVideoStreamSettings(video_stream_info.settings).release()); @@ -430,6 +432,8 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { { mavsdk::Camera::VideoStreamInfo obj; + obj.stream_id = video_stream_info.stream_id(); + obj.settings = translateFromRpcVideoStreamSettings(video_stream_info.settings()); obj.status = translateFromRpcVideoStreamStatus(video_stream_info.status()); @@ -1074,11 +1078,13 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { const mavsdk::Camera::VideoStreamInfoHandle handle = _lazy_plugin.maybe_plugin()->subscribe_video_stream_info( [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( - const mavsdk::Camera::VideoStreamInfo video_stream_info) { + const std::vector video_stream_info) { rpc::camera::VideoStreamInfoResponse rpc_response; - rpc_response.set_allocated_video_stream_info( - translateToRpcVideoStreamInfo(video_stream_info).release()); + for (const auto& elem : video_stream_info) { + auto* ptr = rpc_response.add_video_stream_infos(); + ptr->CopyFrom(*translateToRpcVideoStreamInfo(elem).release()); + } std::unique_lock lock(*subscribe_mutex); if (!*is_finished && !writer->Write(rpc_response)) { diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 8e927bf2f1..fd05e86dc1 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -172,26 +172,157 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return obj; } - static std::unique_ptr - translateToRpcVideoStreaming(const mavsdk::CameraServer::VideoStreaming& video_streaming) + static std::unique_ptr + translateToRpcVideoStreamSettings( + const mavsdk::CameraServer::VideoStreamSettings& video_stream_settings) { - auto rpc_obj = std::make_unique(); + auto rpc_obj = std::make_unique(); - rpc_obj->set_has_rtsp_server(video_streaming.has_rtsp_server); + rpc_obj->set_frame_rate_hz(video_stream_settings.frame_rate_hz); - rpc_obj->set_rtsp_uri(video_streaming.rtsp_uri); + rpc_obj->set_horizontal_resolution_pix(video_stream_settings.horizontal_resolution_pix); + + rpc_obj->set_vertical_resolution_pix(video_stream_settings.vertical_resolution_pix); + + rpc_obj->set_bit_rate_b_s(video_stream_settings.bit_rate_b_s); + + rpc_obj->set_rotation_deg(video_stream_settings.rotation_deg); + + rpc_obj->set_uri(video_stream_settings.uri); + + rpc_obj->set_horizontal_fov_deg(video_stream_settings.horizontal_fov_deg); return rpc_obj; } - static mavsdk::CameraServer::VideoStreaming - translateFromRpcVideoStreaming(const rpc::camera_server::VideoStreaming& video_streaming) + static mavsdk::CameraServer::VideoStreamSettings translateFromRpcVideoStreamSettings( + const rpc::camera_server::VideoStreamSettings& video_stream_settings) { - mavsdk::CameraServer::VideoStreaming obj; + mavsdk::CameraServer::VideoStreamSettings obj; + + obj.frame_rate_hz = video_stream_settings.frame_rate_hz(); + + obj.horizontal_resolution_pix = video_stream_settings.horizontal_resolution_pix(); + + obj.vertical_resolution_pix = video_stream_settings.vertical_resolution_pix(); - obj.has_rtsp_server = video_streaming.has_rtsp_server(); + obj.bit_rate_b_s = video_stream_settings.bit_rate_b_s(); - obj.rtsp_uri = video_streaming.rtsp_uri(); + obj.rotation_deg = video_stream_settings.rotation_deg(); + + obj.uri = video_stream_settings.uri(); + + obj.horizontal_fov_deg = video_stream_settings.horizontal_fov_deg(); + + return obj; + } + + static rpc::camera_server::VideoStreamInfo::VideoStreamStatus translateToRpcVideoStreamStatus( + const mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus& video_stream_status) + { + switch (video_stream_status) { + default: + LogErr() << "Unknown video_stream_status enum value: " + << static_cast(video_stream_status); + // FALLTHROUGH + case mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus::NotRunning: + return rpc::camera_server:: + VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_NOT_RUNNING; + case mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus::InProgress: + return rpc::camera_server:: + VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_IN_PROGRESS; + } + } + + static mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus + translateFromRpcVideoStreamStatus( + const rpc::camera_server::VideoStreamInfo::VideoStreamStatus video_stream_status) + { + switch (video_stream_status) { + default: + LogErr() << "Unknown video_stream_status enum value: " + << static_cast(video_stream_status); + // FALLTHROUGH + case rpc::camera_server:: + VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_NOT_RUNNING: + return mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus::NotRunning; + case rpc::camera_server:: + VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_IN_PROGRESS: + return mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus::InProgress; + } + } + + static rpc::camera_server::VideoStreamInfo::VideoStreamSpectrum + translateToRpcVideoStreamSpectrum( + const mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum& video_stream_spectrum) + { + switch (video_stream_spectrum) { + default: + LogErr() << "Unknown video_stream_spectrum enum value: " + << static_cast(video_stream_spectrum); + // FALLTHROUGH + case mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::Unknown: + return rpc::camera_server:: + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_UNKNOWN; + case mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::VisibleLight: + return rpc::camera_server:: + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT; + case mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::Infrared: + return rpc::camera_server:: + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_INFRARED; + } + } + + static mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum + translateFromRpcVideoStreamSpectrum( + const rpc::camera_server::VideoStreamInfo::VideoStreamSpectrum video_stream_spectrum) + { + switch (video_stream_spectrum) { + default: + LogErr() << "Unknown video_stream_spectrum enum value: " + << static_cast(video_stream_spectrum); + // FALLTHROUGH + case rpc::camera_server:: + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_UNKNOWN: + return mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::Unknown; + case rpc::camera_server:: + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT: + return mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::VisibleLight; + case rpc::camera_server:: + VideoStreamInfo_VideoStreamSpectrum_VIDEO_STREAM_SPECTRUM_INFRARED: + return mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::Infrared; + } + } + + static std::unique_ptr + translateToRpcVideoStreamInfo(const mavsdk::CameraServer::VideoStreamInfo& video_stream_info) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_stream_id(video_stream_info.stream_id); + + rpc_obj->set_allocated_settings( + translateToRpcVideoStreamSettings(video_stream_info.settings).release()); + + rpc_obj->set_status(translateToRpcVideoStreamStatus(video_stream_info.status)); + + rpc_obj->set_spectrum(translateToRpcVideoStreamSpectrum(video_stream_info.spectrum)); + + return rpc_obj; + } + + static mavsdk::CameraServer::VideoStreamInfo + translateFromRpcVideoStreamInfo(const rpc::camera_server::VideoStreamInfo& video_stream_info) + { + mavsdk::CameraServer::VideoStreamInfo obj; + + obj.stream_id = video_stream_info.stream_id(); + + obj.settings = translateFromRpcVideoStreamSettings(video_stream_info.settings()); + + obj.status = translateFromRpcVideoStreamStatus(video_stream_info.status()); + + obj.spectrum = translateFromRpcVideoStreamSpectrum(video_stream_info.spectrum()); return obj; } @@ -630,10 +761,10 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } - grpc::Status SetVideoStreaming( + grpc::Status SetVideoStreamInfo( grpc::ServerContext* /* context */, - const rpc::camera_server::SetVideoStreamingRequest* request, - rpc::camera_server::SetVideoStreamingResponse* response) override + const rpc::camera_server::SetVideoStreamInfoRequest* request, + rpc::camera_server::SetVideoStreamInfoResponse* response) override { if (_lazy_plugin.maybe_plugin() == nullptr) { if (response != nullptr) { @@ -647,12 +778,16 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer } if (request == nullptr) { - LogWarn() << "SetVideoStreaming sent with a null request! Ignoring..."; + LogWarn() << "SetVideoStreamInfo sent with a null request! Ignoring..."; return grpc::Status::OK; } - auto result = _lazy_plugin.maybe_plugin()->set_video_streaming( - translateFromRpcVideoStreaming(request->video_streaming())); + std::vector video_stream_infos_vec; + for (const auto& elem : request->video_stream_infos()) { + video_stream_infos_vec.push_back(translateFromRpcVideoStreamInfo(elem)); + } + + auto result = _lazy_plugin.maybe_plugin()->set_video_stream_info(video_stream_infos_vec); if (response != nullptr) { fillResponseWithResult(response, result); diff --git a/src/mavsdk_server/test/camera_service_impl_test.cpp b/src/mavsdk_server/test/camera_service_impl_test.cpp index ee65d19ce4..b3aecf7ea2 100644 --- a/src/mavsdk_server/test/camera_service_impl_test.cpp +++ b/src/mavsdk_server/test/camera_service_impl_test.cpp @@ -434,7 +434,7 @@ TEST_F(CameraServiceImplTest, registersToVideoStreamInfo) auto rpc_video_stream_info = createArbitraryRPCVideoStreamInfo(); const auto expected_video_stream_info = CameraServiceImpl::translateFromRpcVideoStreamInfo(*rpc_video_stream_info); - mavsdk::CallbackList video_info_callbacks; + mavsdk::CallbackList> video_info_callbacks; EXPECT_CALL(_camera, subscribe_video_stream_info(_)) .WillOnce(SaveResult(&video_info_callbacks, &_callback_saved_promise)); std::vector video_info_events; @@ -443,7 +443,7 @@ TEST_F(CameraServiceImplTest, registersToVideoStreamInfo) auto mode_events_future = subscribeVideoStreamInfoAsync(video_info_events, context); _callback_saved_future.wait(); context->TryCancel(); - video_info_callbacks(expected_video_stream_info); + video_info_callbacks({expected_video_stream_info}); mode_events_future.wait(); } @@ -457,8 +457,10 @@ std::future CameraServiceImplTest::subscribeVideoStreamInfoAsync( mavsdk::rpc::camera::VideoStreamInfoResponse response; while (response_reader->Read(&response)) { - video_info_events.push_back( - CameraServiceImpl::translateFromRpcVideoStreamInfo(response.video_stream_info())); + for (auto& video_stream_info : response.video_stream_infos()) { + video_info_events.push_back( + CameraServiceImpl::translateFromRpcVideoStreamInfo(video_stream_info)); + } } response_reader->Finish(); @@ -490,7 +492,7 @@ void CameraServiceImplTest::checkSendsVideoStreamInfo( { std::promise subscription_promise; auto subscription_future = subscription_promise.get_future(); - mavsdk::CallbackList video_info_callbacks; + mavsdk::CallbackList> video_info_callbacks; auto context = std::make_shared(); EXPECT_CALL(_camera, subscribe_video_stream_info(_)) .WillOnce(SaveResult(&video_info_callbacks, &subscription_promise)); @@ -499,13 +501,12 @@ void CameraServiceImplTest::checkSendsVideoStreamInfo( auto video_info_events_future = subscribeVideoStreamInfoAsync(received_video_info_events, context); subscription_future.wait(); - for (const auto& video_info_event : video_info_events) { - video_info_callbacks(video_info_event); - } + video_info_callbacks(video_info_events); + context->TryCancel(); auto arbitrary_video_info_event = createArbitraryRPCVideoStreamInfo(); video_info_callbacks( - CameraServiceImpl::translateFromRpcVideoStreamInfo(*arbitrary_video_info_event)); + {CameraServiceImpl::translateFromRpcVideoStreamInfo(*arbitrary_video_info_event)}); video_info_events_future.wait(); ASSERT_EQ(video_info_events.size(), received_video_info_events.size()); From 5a4025e5aca80924fa4aa33b610b9e3a79a40842 Mon Sep 17 00:00:00 2001 From: tbago Date: Tue, 27 Feb 2024 14:51:16 +0800 Subject: [PATCH 2/3] Add camera cap flags in camera information * unify camera information in camera and camera server; * add camera cap flags in camera and camera server; * add basic example about camera information; --- examples/camera_server/camera_server.cpp | 13 +- src/mavsdk/plugins/camera/camera.cpp | 49 +- src/mavsdk/plugins/camera/camera_impl.cpp | 68 +++ src/mavsdk/plugins/camera/camera_impl.h | 2 + .../camera/include/plugins/camera/camera.h | 44 ++ .../plugins/camera_server/camera_server.cpp | 41 +- .../camera_server/camera_server_impl.cpp | 58 ++- .../plugins/camera_server/camera_server.h | 32 ++ .../src/generated/camera/camera.pb.cc | 446 +++++++++++++----- .../src/generated/camera/camera.pb.h | 391 ++++++++++++++- .../camera_server/camera_server.pb.cc | 442 ++++++++++------- .../camera_server/camera_server.pb.h | 147 +++++- .../src/plugins/camera/camera_service_impl.h | 102 ++++ .../camera_server_service_impl.h | 97 ++++ 14 files changed, 1595 insertions(+), 337 deletions(-) diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 99a26fdea9..87a203146e 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -34,15 +34,22 @@ int main(int argc, char** argv) auto ret = camera_server.set_information({ .vendor_name = "MAVSDK", .model_name = "Example Camera Server", - .firmware_version = "1.0.0", + .firmware_version = "0.1.0.12", .focal_length_mm = 3.0, .horizontal_sensor_size_mm = 3.68, .vertical_sensor_size_mm = 2.76, .horizontal_resolution_px = 3280, .vertical_resolution_px = 2464, .lens_id = 0, - .definition_file_version = 0, // TODO: add this - .definition_file_uri = "", // TODO: implement this using MAVLink FTP + .definition_file_version = 1, + .definition_file_uri = "http://192.168.0.1/demo.xml", + .camera_cap_flags = + { + mavsdk::CameraServer::Information::CameraCapFlags::CaptureImage, + mavsdk::CameraServer::Information::CameraCapFlags::CaptureVideo, + mavsdk::CameraServer::Information::CameraCapFlags::HasModes, + mavsdk::CameraServer::Information::CameraCapFlags::HasVideoStream, + }, }); // set video stream info diff --git a/src/mavsdk/plugins/camera/camera.cpp b/src/mavsdk/plugins/camera/camera.cpp index 2b51cb7090..cb45a70321 100644 --- a/src/mavsdk/plugins/camera/camera.cpp +++ b/src/mavsdk/plugins/camera/camera.cpp @@ -579,9 +579,42 @@ std::ostream& operator<<(std::ostream& str, Camera::SettingOptions const& settin return str; } +std::ostream& +operator<<(std::ostream& str, Camera::Information::CameraCapFlags const& camera_cap_flags) +{ + switch (camera_cap_flags) { + case Camera::Information::CameraCapFlags::CaptureVideo: + return str << "Capture Video"; + case Camera::Information::CameraCapFlags::CaptureImage: + return str << "Capture Image"; + case Camera::Information::CameraCapFlags::HasModes: + return str << "Has Modes"; + case Camera::Information::CameraCapFlags::CanCaptureImageInVideoMode: + return str << "Can Capture Image In Video Mode"; + case Camera::Information::CameraCapFlags::CanCaptureVideoInImageMode: + return str << "Can Capture Video In Image Mode"; + case Camera::Information::CameraCapFlags::HasImageSurveyMode: + return str << "Has Image Survey Mode"; + case Camera::Information::CameraCapFlags::HasBasicZoom: + return str << "Has Basic Zoom"; + case Camera::Information::CameraCapFlags::HasBasicFocus: + return str << "Has Basic Focus"; + case Camera::Information::CameraCapFlags::HasVideoStream: + return str << "Has Video Stream"; + case Camera::Information::CameraCapFlags::HasTrackingPoint: + return str << "Has Tracking Point"; + case Camera::Information::CameraCapFlags::HasTrackingRectangle: + return str << "Has Tracking Rectangle"; + case Camera::Information::CameraCapFlags::HasTrackingGeoStatus: + return str << "Has Tracking Geo Status"; + default: + return str << "Unknown"; + } +} bool operator==(const Camera::Information& lhs, const Camera::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && + (rhs.firmware_version == lhs.firmware_version) && ((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) || rhs.focal_length_mm == lhs.focal_length_mm) && ((std::isnan(rhs.horizontal_sensor_size_mm) && @@ -590,7 +623,11 @@ bool operator==(const Camera::Information& lhs, const Camera::Information& rhs) ((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) || rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) && (rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) && - (rhs.vertical_resolution_px == lhs.vertical_resolution_px); + (rhs.vertical_resolution_px == lhs.vertical_resolution_px) && + (rhs.lens_id == lhs.lens_id) && + (rhs.definition_file_version == lhs.definition_file_version) && + (rhs.definition_file_uri == lhs.definition_file_uri) && + (rhs.camera_cap_flags == lhs.camera_cap_flags); } std::ostream& operator<<(std::ostream& str, Camera::Information const& information) @@ -599,11 +636,21 @@ std::ostream& operator<<(std::ostream& str, Camera::Information const& informati str << "information:" << '\n' << "{\n"; str << " vendor_name: " << information.vendor_name << '\n'; str << " model_name: " << information.model_name << '\n'; + str << " firmware_version: " << information.firmware_version << '\n'; str << " focal_length_mm: " << information.focal_length_mm << '\n'; str << " horizontal_sensor_size_mm: " << information.horizontal_sensor_size_mm << '\n'; str << " vertical_sensor_size_mm: " << information.vertical_sensor_size_mm << '\n'; str << " horizontal_resolution_px: " << information.horizontal_resolution_px << '\n'; str << " vertical_resolution_px: " << information.vertical_resolution_px << '\n'; + str << " lens_id: " << information.lens_id << '\n'; + str << " definition_file_version: " << information.definition_file_version << '\n'; + str << " definition_file_uri: " << information.definition_file_uri << '\n'; + str << " camera_cap_flags: ["; + for (auto it = information.camera_cap_flags.begin(); it != information.camera_cap_flags.end(); + ++it) { + str << *it; + str << (it + 1 != information.camera_cap_flags.end() ? ", " : "]\n"); + } str << '}'; return str; } diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index 4476834123..571916a13c 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -1166,11 +1166,69 @@ void CameraImpl::process_camera_information(const mavlink_message_t& message) _information.data.vendor_name = (char*)(camera_information.vendor_name); _information.data.model_name = (char*)(camera_information.model_name); + parse_version_int(_information.data.firmware_version, camera_information.firmware_version); _information.data.focal_length_mm = camera_information.focal_length; _information.data.horizontal_sensor_size_mm = camera_information.sensor_size_h; _information.data.vertical_sensor_size_mm = camera_information.sensor_size_v; _information.data.horizontal_resolution_px = camera_information.resolution_h; _information.data.vertical_resolution_px = camera_information.resolution_v; + _information.data.lens_id = camera_information.lens_id; + _information.data.definition_file_version = camera_information.cam_definition_version; + _information.data.definition_file_uri = camera_information.cam_definition_uri; + + // TODO : may need optimize code + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO) != 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::CaptureVideo); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE) != 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::CaptureImage); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES) != 0) { + _information.data.camera_cap_flags.push_back(Camera::Information::CameraCapFlags::HasModes); + } + if ((camera_information.flags & + CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE) != 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::CanCaptureImageInVideoMode); + } + if ((camera_information.flags & + CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE) != 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::CanCaptureVideoInImageMode); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE) != + 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::HasImageSurveyMode); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM) != 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::HasBasicZoom); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS) != 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::HasBasicFocus); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) != 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::HasVideoStream); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT) != 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::HasTrackingPoint); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE) != + 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::HasTrackingRectangle); + } + if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS) != + 0) { + _information.data.camera_cap_flags.push_back( + Camera::Information::CameraCapFlags::HasTrackingGeoStatus); + } _information.subscription_callbacks.queue( _information.data, [this](const auto& func) { _system_impl->call_user_callback(func); }); @@ -2156,4 +2214,14 @@ void CameraImpl::list_photos_async( }).detach(); } +bool CameraImpl::parse_version_int(std::string& version_str, uint32_t version_int) +{ + //(Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff) + std::stringstream ss; + ss << (version_int & 0xff) << "." << (version_int >> 8 & 0xff) << "." + << (version_int >> 16 & 0xff) << "." << (version_int >> 24 & 0xff); + version_str = ss.str(); + return true; +} + } // namespace mavsdk diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index 02cb9e6446..aa78bf4a8f 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -207,6 +207,8 @@ class CameraImpl : public PluginImplBase { void request_missing_capture_info(); + bool parse_version_int(std::string& version_str, uint32_t version_int); + std::unique_ptr _camera_definition{}; bool _is_fetching_camera_definition{false}; bool _has_camera_definition_timed_out{false}; diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index 6a241d92f7..6ac393ef11 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -469,13 +469,57 @@ class Camera : public PluginBase { * @brief Type to represent a camera information. */ struct Information { + /** + * @brief + */ + enum class CameraCapFlags { + CaptureVideo, /**< @brief Camera is able to record video. */ + CaptureImage, /**< @brief Camera is able to capture images. */ + HasModes, /**< @brief Camera has separate Video and Image/Photo modes + (MAV_CMD_SET_CAMERA_MODE). */ + CanCaptureImageInVideoMode, /**< @brief Camera can capture images while in video mode. + */ + CanCaptureVideoInImageMode, /**< @brief Camera can capture videos while in Photo/Image + mode. */ + HasImageSurveyMode, /**< @brief Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE). + */ + HasBasicZoom, /**< @brief Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM). */ + HasBasicFocus, /**< @brief Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS). */ + HasVideoStream, /**< @brief Camera has video streaming capabilities (request + VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video + streaming info). */ + HasTrackingPoint, /**< @brief Camera supports tracking of a point on the camera view.. + */ + HasTrackingRectangle, /**< @brief Camera supports tracking of a selection rectangle on + the camera view.. */ + HasTrackingGeoStatus, /**< @brief Camera supports tracking geo status + (CAMERA_TRACKING_GEO_STATUS).. */ + }; + + /** + * @brief Stream operator to print information about a `Camera::CameraCapFlags`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, Camera::Information::CameraCapFlags const& camera_cap_flags); + std::string vendor_name{}; /**< @brief Name of the camera vendor */ std::string model_name{}; /**< @brief Name of the camera model */ + std::string firmware_version{}; /**< @brief Camera firmware version in + major[.minor[.patch[.dev]]] format */ float focal_length_mm{}; /**< @brief Focal length */ float horizontal_sensor_size_mm{}; /**< @brief Horizontal sensor size */ float vertical_sensor_size_mm{}; /**< @brief Vertical sensor size */ uint32_t horizontal_resolution_px{}; /**< @brief Horizontal image resolution in pixels */ uint32_t vertical_resolution_px{}; /**< @brief Vertical image resolution in pixels */ + uint32_t lens_id{}; /**< @brief Lens ID */ + uint32_t + definition_file_version{}; /**< @brief Camera definition file version (iteration) */ + std::string + definition_file_uri{}; /**< @brief Camera definition URI (http or mavlink ftp) */ + std::vector + camera_cap_flags{}; /**< @brief Camera capability flags (Array) */ }; /** diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 45ba39cf4e..0f1c7f4455 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -207,6 +207,38 @@ CameraServer::respond_reset_settings(CameraFeedback reset_settings_feedback) con return _impl->respond_reset_settings(reset_settings_feedback); } +std::ostream& +operator<<(std::ostream& str, CameraServer::Information::CameraCapFlags const& camera_cap_flags) +{ + switch (camera_cap_flags) { + case CameraServer::Information::CameraCapFlags::CaptureVideo: + return str << "Capture Video"; + case CameraServer::Information::CameraCapFlags::CaptureImage: + return str << "Capture Image"; + case CameraServer::Information::CameraCapFlags::HasModes: + return str << "Has Modes"; + case CameraServer::Information::CameraCapFlags::CanCaptureImageInVideoMode: + return str << "Can Capture Image In Video Mode"; + case CameraServer::Information::CameraCapFlags::CanCaptureVideoInImageMode: + return str << "Can Capture Video In Image Mode"; + case CameraServer::Information::CameraCapFlags::HasImageSurveyMode: + return str << "Has Image Survey Mode"; + case CameraServer::Information::CameraCapFlags::HasBasicZoom: + return str << "Has Basic Zoom"; + case CameraServer::Information::CameraCapFlags::HasBasicFocus: + return str << "Has Basic Focus"; + case CameraServer::Information::CameraCapFlags::HasVideoStream: + return str << "Has Video Stream"; + case CameraServer::Information::CameraCapFlags::HasTrackingPoint: + return str << "Has Tracking Point"; + case CameraServer::Information::CameraCapFlags::HasTrackingRectangle: + return str << "Has Tracking Rectangle"; + case CameraServer::Information::CameraCapFlags::HasTrackingGeoStatus: + return str << "Has Tracking Geo Status"; + default: + return str << "Unknown"; + } +} bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && @@ -222,7 +254,8 @@ bool operator==(const CameraServer::Information& lhs, const CameraServer::Inform (rhs.vertical_resolution_px == lhs.vertical_resolution_px) && (rhs.lens_id == lhs.lens_id) && (rhs.definition_file_version == lhs.definition_file_version) && - (rhs.definition_file_uri == lhs.definition_file_uri); + (rhs.definition_file_uri == lhs.definition_file_uri) && + (rhs.camera_cap_flags == lhs.camera_cap_flags); } std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information) @@ -240,6 +273,12 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Information const& inf str << " lens_id: " << information.lens_id << '\n'; str << " definition_file_version: " << information.definition_file_version << '\n'; str << " definition_file_uri: " << information.definition_file_uri << '\n'; + str << " camera_cap_flags: ["; + for (auto it = information.camera_cap_flags.begin(); it != information.camera_cap_flags.end(); + ++it) { + str << *it; + str << (it + 1 != information.camera_cap_flags.end() ? ", " : "]\n"); + } str << '}'; return str; } diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index b1001b2733..7a6df9b36a 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -820,23 +820,49 @@ std::optional CameraServerImpl::process_camera_informatio uint32_t firmware_version; parse_version_string(_information.firmware_version, firmware_version); - // capability flags are determined by subscriptions + // build capability from camera server information.camera_cap_flags uint32_t capability_flags{}; - - if (!_take_photo_callbacks.empty()) { - capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE; - } - - if (!_start_video_callbacks.empty()) { - capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO; - } - - if (!_set_mode_callbacks.empty()) { - capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES; - } - - if (_is_video_stream_info_set) { - capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; + for (auto capability_flag : _information.camera_cap_flags) { + switch (capability_flag) { + case CameraServer::Information::CameraCapFlags::CaptureVideo: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO; + break; + case CameraServer::Information::CameraCapFlags::CaptureImage: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE; + break; + case CameraServer::Information::CameraCapFlags::HasModes: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES; + break; + case CameraServer::Information::CameraCapFlags::CanCaptureImageInVideoMode: + capability_flags |= + CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; + break; + case CameraServer::Information::CameraCapFlags::CanCaptureVideoInImageMode: + capability_flags |= + CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; + break; + case CameraServer::Information::CameraCapFlags::HasImageSurveyMode: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE; + break; + case CameraServer::Information::CameraCapFlags::HasBasicZoom: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; + break; + case CameraServer::Information::CameraCapFlags::HasBasicFocus: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; + break; + case CameraServer::Information::CameraCapFlags::HasVideoStream: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; + break; + case CameraServer::Information::CameraCapFlags::HasTrackingPoint: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT; + break; + case CameraServer::Information::CameraCapFlags::HasTrackingRectangle: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE; + break; + case CameraServer::Information::CameraCapFlags::HasTrackingGeoStatus: + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS; + break; + } } _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name)); diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index 40e7ca91a8..a56ecd6546 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -83,6 +83,37 @@ class CameraServer : public ServerPluginBase { * @brief Type to represent a camera information. */ struct Information { + /** + * @brief + */ + enum class CameraCapFlags { + CaptureVideo, /**< @brief Camera is able to record video. */ + CaptureImage, /**< @brief Camera is able to capture images. */ + HasModes, /**< @brief Camera has separate Video and Image/Photo modes. */ + CanCaptureImageInVideoMode, /**< @brief Camera can capture images while in video mode. + */ + CanCaptureVideoInImageMode, /**< @brief Camera can capture videos while in Photo/Image + mode. */ + HasImageSurveyMode, /**< @brief Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE). + */ + HasBasicZoom, /**< @brief Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM). */ + HasBasicFocus, /**< @brief Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS). */ + HasVideoStream, /**< @brief Camera has video streaming capabilities (request. */ + HasTrackingPoint, /**< @brief Camera supports tracking of a point on the camera view.. + */ + HasTrackingRectangle, /**< @brief Camera supports tracking of a selection rectangle on + the. */ + HasTrackingGeoStatus, /**< @brief Camera supports tracking geo status. */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::CameraCapFlags`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<( + std::ostream& str, CameraServer::Information::CameraCapFlags const& camera_cap_flags); + std::string vendor_name{}; /**< @brief Name of the camera vendor */ std::string model_name{}; /**< @brief Name of the camera model */ std::string firmware_version{}; /**< @brief Camera firmware version in @@ -97,6 +128,7 @@ class CameraServer : public ServerPluginBase { definition_file_version{}; /**< @brief Camera definition file version (iteration) */ std::string definition_file_uri{}; /**< @brief Camera definition URI (http or mavlink ftp) */ + std::vector camera_cap_flags{}; /**< @brief Camera capability flags */ }; /** diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.cc b/src/mavsdk_server/src/generated/camera/camera.pb.cc index 5e0321c047..67167a72a3 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.pb.cc @@ -440,17 +440,27 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr Information::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : vendor_name_( + : camera_cap_flags_{}, + _camera_cap_flags_cached_byte_size_{0}, + vendor_name_( &::google::protobuf::internal::fixed_address_empty_string, ::_pbi::ConstantInitialized()), model_name_( &::google::protobuf::internal::fixed_address_empty_string, ::_pbi::ConstantInitialized()), + firmware_version_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + definition_file_uri_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), focal_length_mm_{0}, horizontal_sensor_size_mm_{0}, vertical_sensor_size_mm_{0}, horizontal_resolution_px_{0u}, vertical_resolution_px_{0u}, + lens_id_{0u}, + definition_file_version_{0u}, _cached_size_{0} {} template @@ -1072,7 +1082,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace rpc } // namespace mavsdk static ::_pb::Metadata file_level_metadata_camera_2fcamera_2eproto[56]; -static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_2fcamera_2eproto[7]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_2fcamera_2eproto[8]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_2fcamera_2eproto = nullptr; const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( @@ -1648,11 +1658,16 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.vendor_name_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.model_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.firmware_version_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.focal_length_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.horizontal_sensor_size_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.vertical_sensor_size_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.horizontal_resolution_px_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.vertical_resolution_px_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.lens_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.definition_file_version_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.definition_file_uri_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.camera_cap_flags_), }; static const ::_pbi::MigrationSchema @@ -1904,76 +1919,93 @@ const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_ "\010\"\177\n\016SettingOptions\022\022\n\nsetting_id\030\001 \001(\t\022" "\033\n\023setting_description\030\002 \001(\t\022*\n\007options\030" "\003 \003(\0132\031.mavsdk.rpc.camera.Option\022\020\n\010is_r" - "ange\030\004 \001(\010\"\325\001\n\013Information\022\023\n\013vendor_nam" - "e\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\027\n\017focal_len" - "gth_mm\030\003 \001(\002\022!\n\031horizontal_sensor_size_m" - "m\030\004 \001(\002\022\037\n\027vertical_sensor_size_mm\030\005 \001(\002" - "\022 \n\030horizontal_resolution_px\030\006 \001(\r\022\036\n\026ve" - "rtical_resolution_px\030\007 \001(\r*8\n\004Mode\022\020\n\014MO" - "DE_UNKNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VID" - "EO\020\002*F\n\013PhotosRange\022\024\n\020PHOTOS_RANGE_ALL\020" - "\000\022!\n\035PHOTOS_RANGE_SINCE_CONNECTION\020\0012\271\022\n" - "\rCameraService\022R\n\007Prepare\022!.mavsdk.rpc.c" - "amera.PrepareRequest\032\".mavsdk.rpc.camera" - ".PrepareResponse\"\000\022X\n\tTakePhoto\022#.mavsdk" - ".rpc.camera.TakePhotoRequest\032$.mavsdk.rp" - "c.camera.TakePhotoResponse\"\000\022s\n\022StartPho" - "toInterval\022,.mavsdk.rpc.camera.StartPhot" - "oIntervalRequest\032-.mavsdk.rpc.camera.Sta" - "rtPhotoIntervalResponse\"\000\022p\n\021StopPhotoIn" - "terval\022+.mavsdk.rpc.camera.StopPhotoInte" - "rvalRequest\032,.mavsdk.rpc.camera.StopPhot" - "oIntervalResponse\"\000\022[\n\nStartVideo\022$.mavs" - "dk.rpc.camera.StartVideoRequest\032%.mavsdk" - ".rpc.camera.StartVideoResponse\"\000\022X\n\tStop" - "Video\022#.mavsdk.rpc.camera.StopVideoReque" - "st\032$.mavsdk.rpc.camera.StopVideoResponse" - "\"\000\022z\n\023StartVideoStreaming\022-.mavsdk.rpc.c" - "amera.StartVideoStreamingRequest\032..mavsd" - "k.rpc.camera.StartVideoStreamingResponse" - "\"\004\200\265\030\001\022w\n\022StopVideoStreaming\022,.mavsdk.rp" - "c.camera.StopVideoStreamingRequest\032-.mav" - "sdk.rpc.camera.StopVideoStreamingRespons" - "e\"\004\200\265\030\001\022R\n\007SetMode\022!.mavsdk.rpc.camera.S" - "etModeRequest\032\".mavsdk.rpc.camera.SetMod" - "eResponse\"\000\022[\n\nListPhotos\022$.mavsdk.rpc.c" - "amera.ListPhotosRequest\032%.mavsdk.rpc.cam" - "era.ListPhotosResponse\"\000\022]\n\rSubscribeMod" - "e\022\'.mavsdk.rpc.camera.SubscribeModeReque" - "st\032\037.mavsdk.rpc.camera.ModeResponse\"\0000\001\022" - "r\n\024SubscribeInformation\022..mavsdk.rpc.cam" - "era.SubscribeInformationRequest\032&.mavsdk" - ".rpc.camera.InformationResponse\"\0000\001\022~\n\030S" - "ubscribeVideoStreamInfo\0222.mavsdk.rpc.cam" - "era.SubscribeVideoStreamInfoRequest\032*.ma" - "vsdk.rpc.camera.VideoStreamInfoResponse\"" - "\0000\001\022v\n\024SubscribeCaptureInfo\022..mavsdk.rpc" - ".camera.SubscribeCaptureInfoRequest\032&.ma" - "vsdk.rpc.camera.CaptureInfoResponse\"\004\200\265\030" - "\0000\001\022c\n\017SubscribeStatus\022).mavsdk.rpc.came" - "ra.SubscribeStatusRequest\032!.mavsdk.rpc.c" - "amera.StatusResponse\"\0000\001\022\202\001\n\030SubscribeCu" - "rrentSettings\0222.mavsdk.rpc.camera.Subscr" - "ibeCurrentSettingsRequest\032*.mavsdk.rpc.c" - "amera.CurrentSettingsResponse\"\004\200\265\030\0000\001\022\223\001" - "\n\037SubscribePossibleSettingOptions\0229.mavs" - "dk.rpc.camera.SubscribePossibleSettingOp" - "tionsRequest\0321.mavsdk.rpc.camera.Possibl" - "eSettingOptionsResponse\"\0000\001\022[\n\nSetSettin" - "g\022$.mavsdk.rpc.camera.SetSettingRequest\032" - "%.mavsdk.rpc.camera.SetSettingResponse\"\000" - "\022[\n\nGetSetting\022$.mavsdk.rpc.camera.GetSe" - "ttingRequest\032%.mavsdk.rpc.camera.GetSett" - "ingResponse\"\000\022d\n\rFormatStorage\022\'.mavsdk." - "rpc.camera.FormatStorageRequest\032(.mavsdk" - ".rpc.camera.FormatStorageResponse\"\000\022e\n\014S" - "electCamera\022&.mavsdk.rpc.camera.SelectCa" - "meraRequest\032\'.mavsdk.rpc.camera.SelectCa" - "meraResponse\"\004\200\265\030\001\022d\n\rResetSettings\022\'.ma" - "vsdk.rpc.camera.ResetSettingsRequest\032(.m" - "avsdk.rpc.camera.ResetSettingsResponse\"\000" - "B\037\n\020io.mavsdk.cameraB\013CameraProtob\006proto" - "3" + "ange\030\004 \001(\010\"\220\007\n\013Information\022\023\n\013vendor_nam" + "e\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\030\n\020firmware_" + "version\030\003 \001(\t\022\027\n\017focal_length_mm\030\004 \001(\002\022!" + "\n\031horizontal_sensor_size_mm\030\005 \001(\002\022\037\n\027ver" + "tical_sensor_size_mm\030\006 \001(\002\022 \n\030horizontal" + "_resolution_px\030\007 \001(\r\022\036\n\026vertical_resolut" + "ion_px\030\010 \001(\r\022\017\n\007lens_id\030\t \001(\r\022\037\n\027definit" + "ion_file_version\030\n \001(\r\022\033\n\023definition_fil" + "e_uri\030\013 \001(\t\022G\n\020camera_cap_flags\030\014 \003(\0162-." + "mavsdk.rpc.camera.Information.CameraCapF" + "lags\"\206\004\n\016CameraCapFlags\022\"\n\036CAMERA_CAP_FL" + "AGS_CAPTURE_VIDEO\020\000\022\"\n\036CAMERA_CAP_FLAGS_" + "CAPTURE_IMAGE\020\001\022\036\n\032CAMERA_CAP_FLAGS_HAS_" + "MODES\020\002\0224\n0CAMERA_CAP_FLAGS_CAN_CAPTURE_" + "IMAGE_IN_VIDEO_MODE\020\003\0224\n0CAMERA_CAP_FLAG" + "S_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE\020\004\022*\n&C" + "AMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE\020\005\022" + "#\n\037CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM\020\006\022$\n " + "CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS\020\007\022%\n!CA" + "MERA_CAP_FLAGS_HAS_VIDEO_STREAM\020\010\022\'\n#CAM" + "ERA_CAP_FLAGS_HAS_TRACKING_POINT\020\t\022+\n\'CA" + "MERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE\020\n\022" + ",\n(CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STA" + "TUS\020\013*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_" + "PHOTO\020\001\022\016\n\nMODE_VIDEO\020\002*F\n\013PhotosRange\022\024" + "\n\020PHOTOS_RANGE_ALL\020\000\022!\n\035PHOTOS_RANGE_SIN" + "CE_CONNECTION\020\0012\271\022\n\rCameraService\022R\n\007Pre" + "pare\022!.mavsdk.rpc.camera.PrepareRequest\032" + "\".mavsdk.rpc.camera.PrepareResponse\"\000\022X\n" + "\tTakePhoto\022#.mavsdk.rpc.camera.TakePhoto" + "Request\032$.mavsdk.rpc.camera.TakePhotoRes" + "ponse\"\000\022s\n\022StartPhotoInterval\022,.mavsdk.r" + "pc.camera.StartPhotoIntervalRequest\032-.ma" + "vsdk.rpc.camera.StartPhotoIntervalRespon" + "se\"\000\022p\n\021StopPhotoInterval\022+.mavsdk.rpc.c" + "amera.StopPhotoIntervalRequest\032,.mavsdk." + "rpc.camera.StopPhotoIntervalResponse\"\000\022[" + "\n\nStartVideo\022$.mavsdk.rpc.camera.StartVi" + "deoRequest\032%.mavsdk.rpc.camera.StartVide" + "oResponse\"\000\022X\n\tStopVideo\022#.mavsdk.rpc.ca" + "mera.StopVideoRequest\032$.mavsdk.rpc.camer" + "a.StopVideoResponse\"\000\022z\n\023StartVideoStrea" + "ming\022-.mavsdk.rpc.camera.StartVideoStrea" + "mingRequest\032..mavsdk.rpc.camera.StartVid" + "eoStreamingResponse\"\004\200\265\030\001\022w\n\022StopVideoSt" + "reaming\022,.mavsdk.rpc.camera.StopVideoStr" + "eamingRequest\032-.mavsdk.rpc.camera.StopVi" + "deoStreamingResponse\"\004\200\265\030\001\022R\n\007SetMode\022!." + "mavsdk.rpc.camera.SetModeRequest\032\".mavsd" + "k.rpc.camera.SetModeResponse\"\000\022[\n\nListPh" + "otos\022$.mavsdk.rpc.camera.ListPhotosReque" + "st\032%.mavsdk.rpc.camera.ListPhotosRespons" + "e\"\000\022]\n\rSubscribeMode\022\'.mavsdk.rpc.camera" + ".SubscribeModeRequest\032\037.mavsdk.rpc.camer" + "a.ModeResponse\"\0000\001\022r\n\024SubscribeInformati" + "on\022..mavsdk.rpc.camera.SubscribeInformat" + "ionRequest\032&.mavsdk.rpc.camera.Informati" + "onResponse\"\0000\001\022~\n\030SubscribeVideoStreamIn" + "fo\0222.mavsdk.rpc.camera.SubscribeVideoStr" + "eamInfoRequest\032*.mavsdk.rpc.camera.Video" + "StreamInfoResponse\"\0000\001\022v\n\024SubscribeCaptu" + "reInfo\022..mavsdk.rpc.camera.SubscribeCapt" + "ureInfoRequest\032&.mavsdk.rpc.camera.Captu" + "reInfoResponse\"\004\200\265\030\0000\001\022c\n\017SubscribeStatu" + "s\022).mavsdk.rpc.camera.SubscribeStatusReq" + "uest\032!.mavsdk.rpc.camera.StatusResponse\"" + "\0000\001\022\202\001\n\030SubscribeCurrentSettings\0222.mavsd" + "k.rpc.camera.SubscribeCurrentSettingsReq" + "uest\032*.mavsdk.rpc.camera.CurrentSettings" + "Response\"\004\200\265\030\0000\001\022\223\001\n\037SubscribePossibleSe" + "ttingOptions\0229.mavsdk.rpc.camera.Subscri" + "bePossibleSettingOptionsRequest\0321.mavsdk" + ".rpc.camera.PossibleSettingOptionsRespon" + "se\"\0000\001\022[\n\nSetSetting\022$.mavsdk.rpc.camera" + ".SetSettingRequest\032%.mavsdk.rpc.camera.S" + "etSettingResponse\"\000\022[\n\nGetSetting\022$.mavs" + "dk.rpc.camera.GetSettingRequest\032%.mavsdk" + ".rpc.camera.GetSettingResponse\"\000\022d\n\rForm" + "atStorage\022\'.mavsdk.rpc.camera.FormatStor" + "ageRequest\032(.mavsdk.rpc.camera.FormatSto" + "rageResponse\"\000\022e\n\014SelectCamera\022&.mavsdk." + "rpc.camera.SelectCameraRequest\032\'.mavsdk." + "rpc.camera.SelectCameraResponse\"\004\200\265\030\001\022d\n" + "\rResetSettings\022\'.mavsdk.rpc.camera.Reset" + "SettingsRequest\032(.mavsdk.rpc.camera.Rese" + "tSettingsResponse\"\000B\037\n\020io.mavsdk.cameraB" + "\013CameraProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_2fcamera_2eproto_deps[1] = { @@ -1983,7 +2015,7 @@ static ::absl::once_flag descriptor_table_camera_2fcamera_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_camera_2fcamera_2eproto = { false, false, - 7961, + 8660, descriptor_table_protodef_camera_2fcamera_2eproto, "camera/camera.proto", &descriptor_table_camera_2fcamera_2eproto_once, @@ -2133,10 +2165,40 @@ constexpr int Status::StorageType_ARRAYSIZE; #endif // (__cplusplus < 201703) && // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) -const ::google::protobuf::EnumDescriptor* Mode_descriptor() { +const ::google::protobuf::EnumDescriptor* Information_CameraCapFlags_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_2fcamera_2eproto); return file_level_enum_descriptors_camera_2fcamera_2eproto[5]; } +PROTOBUF_CONSTINIT const uint32_t Information_CameraCapFlags_internal_data_[] = { + 786432u, 0u, }; +bool Information_CameraCapFlags_IsValid(int value) { + return 0 <= value && value <= 11; +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_CAPTURE_VIDEO; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_CAPTURE_IMAGE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_MODES; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS; +constexpr Information_CameraCapFlags Information::CameraCapFlags_MIN; +constexpr Information_CameraCapFlags Information::CameraCapFlags_MAX; +constexpr int Information::CameraCapFlags_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::google::protobuf::EnumDescriptor* Mode_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_2fcamera_2eproto); + return file_level_enum_descriptors_camera_2fcamera_2eproto[6]; +} PROTOBUF_CONSTINIT const uint32_t Mode_internal_data_[] = { 196608u, 0u, }; bool Mode_IsValid(int value) { @@ -2144,7 +2206,7 @@ bool Mode_IsValid(int value) { } const ::google::protobuf::EnumDescriptor* PhotosRange_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_2fcamera_2eproto); - return file_level_enum_descriptors_camera_2fcamera_2eproto[6]; + return file_level_enum_descriptors_camera_2fcamera_2eproto[7]; } PROTOBUF_CONSTINIT const uint32_t PhotosRange_internal_data_[] = { 131072u, 0u, }; @@ -12197,8 +12259,12 @@ Information::Information(::google::protobuf::Arena* arena) inline PROTOBUF_NDEBUG_INLINE Information::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) - : vendor_name_(arena, from.vendor_name_), + : camera_cap_flags_{visibility, arena, from.camera_cap_flags_}, + _camera_cap_flags_cached_byte_size_{0}, + vendor_name_(arena, from.vendor_name_), model_name_(arena, from.model_name_), + firmware_version_(arena, from.firmware_version_), + definition_file_uri_(arena, from.definition_file_uri_), _cached_size_{0} {} Information::Information( @@ -12214,17 +12280,21 @@ Information::Information( offsetof(Impl_, focal_length_mm_), reinterpret_cast(&from._impl_) + offsetof(Impl_, focal_length_mm_), - offsetof(Impl_, vertical_resolution_px_) - + offsetof(Impl_, definition_file_version_) - offsetof(Impl_, focal_length_mm_) + - sizeof(Impl_::vertical_resolution_px_)); + sizeof(Impl_::definition_file_version_)); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.Information) } inline PROTOBUF_NDEBUG_INLINE Information::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : vendor_name_(arena), + : camera_cap_flags_{visibility, arena}, + _camera_cap_flags_cached_byte_size_{0}, + vendor_name_(arena), model_name_(arena), + firmware_version_(arena), + definition_file_uri_(arena), _cached_size_{0} {} inline void Information::SharedCtor(::_pb::Arena* arena) { @@ -12232,9 +12302,9 @@ inline void Information::SharedCtor(::_pb::Arena* arena) { ::memset(reinterpret_cast(&_impl_) + offsetof(Impl_, focal_length_mm_), 0, - offsetof(Impl_, vertical_resolution_px_) - + offsetof(Impl_, definition_file_version_) - offsetof(Impl_, focal_length_mm_) + - sizeof(Impl_::vertical_resolution_px_)); + sizeof(Impl_::definition_file_version_)); } Information::~Information() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.Information) @@ -12245,6 +12315,8 @@ inline void Information::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.vendor_name_.Destroy(); _impl_.model_name_.Destroy(); + _impl_.firmware_version_.Destroy(); + _impl_.definition_file_uri_.Destroy(); _impl_.~Impl_(); } @@ -12255,11 +12327,14 @@ PROTOBUF_NOINLINE void Information::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; + _impl_.camera_cap_flags_.Clear(); _impl_.vendor_name_.ClearToEmpty(); _impl_.model_name_.ClearToEmpty(); + _impl_.firmware_version_.ClearToEmpty(); + _impl_.definition_file_uri_.ClearToEmpty(); ::memset(&_impl_.focal_length_mm_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.vertical_resolution_px_) - - reinterpret_cast(&_impl_.focal_length_mm_)) + sizeof(_impl_.vertical_resolution_px_)); + reinterpret_cast(&_impl_.definition_file_version_) - + reinterpret_cast(&_impl_.focal_length_mm_)) + sizeof(_impl_.definition_file_version_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -12271,15 +12346,15 @@ const char* Information::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<3, 7, 0, 59, 2> Information::_table_ = { +const ::_pbi::TcParseTable<4, 12, 0, 102, 2> Information::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 7, 56, // max_field_number, fast_idx_mask + 12, 120, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967168, // skipmap + 4294963200, // skipmap offsetof(decltype(_table_), field_entries), - 7, // num_field_entries + 12, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_Information_default_instance_._instance, @@ -12292,21 +12367,39 @@ const ::_pbi::TcParseTable<3, 7, 0, 59, 2> Information::_table_ = { // string model_name = 2; {::_pbi::TcParser::FastUS1, {18, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.model_name_)}}, - // float focal_length_mm = 3; + // string firmware_version = 3; + {::_pbi::TcParser::FastUS1, + {26, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.firmware_version_)}}, + // float focal_length_mm = 4; {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.focal_length_mm_)}}, - // float horizontal_sensor_size_mm = 4; + {37, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.focal_length_mm_)}}, + // float horizontal_sensor_size_mm = 5; {::_pbi::TcParser::FastF32S1, - {37, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.horizontal_sensor_size_mm_)}}, - // float vertical_sensor_size_mm = 5; + {45, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.horizontal_sensor_size_mm_)}}, + // float vertical_sensor_size_mm = 6; {::_pbi::TcParser::FastF32S1, - {45, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.vertical_sensor_size_mm_)}}, - // uint32 horizontal_resolution_px = 6; + {53, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.vertical_sensor_size_mm_)}}, + // uint32 horizontal_resolution_px = 7; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Information, _impl_.horizontal_resolution_px_), 63>(), - {48, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.horizontal_resolution_px_)}}, - // uint32 vertical_resolution_px = 7; + {56, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.horizontal_resolution_px_)}}, + // uint32 vertical_resolution_px = 8; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Information, _impl_.vertical_resolution_px_), 63>(), - {56, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.vertical_resolution_px_)}}, + {64, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.vertical_resolution_px_)}}, + // uint32 lens_id = 9; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Information, _impl_.lens_id_), 63>(), + {72, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.lens_id_)}}, + // uint32 definition_file_version = 10; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Information, _impl_.definition_file_version_), 63>(), + {80, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_version_)}}, + // string definition_file_uri = 11; + {::_pbi::TcParser::FastUS1, + {90, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_uri_)}}, + // repeated .mavsdk.rpc.camera.Information.CameraCapFlags camera_cap_flags = 12; + {::_pbi::TcParser::FastV32P1, + {98, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.camera_cap_flags_)}}, + {::_pbi::TcParser::MiniParse, {}}, + {::_pbi::TcParser::MiniParse, {}}, + {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ @@ -12316,28 +12409,45 @@ const ::_pbi::TcParseTable<3, 7, 0, 59, 2> Information::_table_ = { // string model_name = 2; {PROTOBUF_FIELD_OFFSET(Information, _impl_.model_name_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // float focal_length_mm = 3; + // string firmware_version = 3; + {PROTOBUF_FIELD_OFFSET(Information, _impl_.firmware_version_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // float focal_length_mm = 4; {PROTOBUF_FIELD_OFFSET(Information, _impl_.focal_length_mm_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; {PROTOBUF_FIELD_OFFSET(Information, _impl_.horizontal_sensor_size_mm_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; {PROTOBUF_FIELD_OFFSET(Information, _impl_.vertical_sensor_size_mm_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; {PROTOBUF_FIELD_OFFSET(Information, _impl_.horizontal_resolution_px_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; {PROTOBUF_FIELD_OFFSET(Information, _impl_.vertical_resolution_px_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // uint32 lens_id = 9; + {PROTOBUF_FIELD_OFFSET(Information, _impl_.lens_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // uint32 definition_file_version = 10; + {PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_version_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // string definition_file_uri = 11; + {PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_uri_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // repeated .mavsdk.rpc.camera.Information.CameraCapFlags camera_cap_flags = 12; + {PROTOBUF_FIELD_OFFSET(Information, _impl_.camera_cap_flags_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kPackedOpenEnum)}, }}, // no aux_entries {{ - "\35\13\12\0\0\0\0\0" + "\35\13\12\20\0\0\0\0\0\0\0\23\0\0\0\0" "mavsdk.rpc.camera.Information" "vendor_name" "model_name" + "firmware_version" + "definition_file_uri" }}, }; @@ -12364,7 +12474,15 @@ ::uint8_t* Information::_InternalSerialize( target = stream->WriteStringMaybeAliased(2, _s, target); } - // float focal_length_mm = 3; + // string firmware_version = 3; + if (!this->_internal_firmware_version().empty()) { + const std::string& _s = this->_internal_firmware_version(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera.Information.firmware_version"); + target = stream->WriteStringMaybeAliased(3, _s, target); + } + + // float focal_length_mm = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_focal_length_mm = this->_internal_focal_length_mm(); @@ -12373,10 +12491,10 @@ ::uint8_t* Information::_InternalSerialize( if (raw_focal_length_mm != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_focal_length_mm(), target); + 4, this->_internal_focal_length_mm(), target); } - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_horizontal_sensor_size_mm = this->_internal_horizontal_sensor_size_mm(); @@ -12385,10 +12503,10 @@ ::uint8_t* Information::_InternalSerialize( if (raw_horizontal_sensor_size_mm != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 4, this->_internal_horizontal_sensor_size_mm(), target); + 5, this->_internal_horizontal_sensor_size_mm(), target); } - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_vertical_sensor_size_mm = this->_internal_vertical_sensor_size_mm(); @@ -12397,21 +12515,52 @@ ::uint8_t* Information::_InternalSerialize( if (raw_vertical_sensor_size_mm != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 5, this->_internal_vertical_sensor_size_mm(), target); + 6, this->_internal_vertical_sensor_size_mm(), target); } - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; if (this->_internal_horizontal_resolution_px() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteUInt32ToArray( - 6, this->_internal_horizontal_resolution_px(), target); + 7, this->_internal_horizontal_resolution_px(), target); } - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; if (this->_internal_vertical_resolution_px() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteUInt32ToArray( - 7, this->_internal_vertical_resolution_px(), target); + 8, this->_internal_vertical_resolution_px(), target); + } + + // uint32 lens_id = 9; + if (this->_internal_lens_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 9, this->_internal_lens_id(), target); + } + + // uint32 definition_file_version = 10; + if (this->_internal_definition_file_version() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 10, this->_internal_definition_file_version(), target); + } + + // string definition_file_uri = 11; + if (!this->_internal_definition_file_uri().empty()) { + const std::string& _s = this->_internal_definition_file_uri(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera.Information.definition_file_uri"); + target = stream->WriteStringMaybeAliased(11, _s, target); + } + + // repeated .mavsdk.rpc.camera.Information.CameraCapFlags camera_cap_flags = 12; + { + std::size_t byte_size = _impl_._camera_cap_flags_cached_byte_size_.Get(); + if (byte_size > 0) { + target = stream->WriteEnumPacked(12, _internal_camera_cap_flags(), + byte_size, target); + } } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -12431,6 +12580,23 @@ ::size_t Information::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; + // repeated .mavsdk.rpc.camera.Information.CameraCapFlags camera_cap_flags = 12; + { + std::size_t data_size = 0; + auto count = static_cast(this->_internal_camera_cap_flags_size()); + + for (std::size_t i = 0; i < count; ++i) { + data_size += ::_pbi::WireFormatLite::EnumSize( + this->_internal_camera_cap_flags().Get(static_cast(i))); + } + total_size += data_size; + if (data_size > 0) { + total_size += 1; + total_size += ::_pbi::WireFormatLite::Int32Size( + static_cast(data_size)); + } + _impl_._camera_cap_flags_cached_byte_size_.Set(::_pbi::ToCachedSize(data_size)); + } // string vendor_name = 1; if (!this->_internal_vendor_name().empty()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( @@ -12443,7 +12609,19 @@ ::size_t Information::ByteSizeLong() const { this->_internal_model_name()); } - // float focal_length_mm = 3; + // string firmware_version = 3; + if (!this->_internal_firmware_version().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_firmware_version()); + } + + // string definition_file_uri = 11; + if (!this->_internal_definition_file_uri().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_definition_file_uri()); + } + + // float focal_length_mm = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_focal_length_mm = this->_internal_focal_length_mm(); @@ -12453,7 +12631,7 @@ ::size_t Information::ByteSizeLong() const { total_size += 5; } - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_horizontal_sensor_size_mm = this->_internal_horizontal_sensor_size_mm(); @@ -12463,7 +12641,7 @@ ::size_t Information::ByteSizeLong() const { total_size += 5; } - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_vertical_sensor_size_mm = this->_internal_vertical_sensor_size_mm(); @@ -12473,18 +12651,30 @@ ::size_t Information::ByteSizeLong() const { total_size += 5; } - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; if (this->_internal_horizontal_resolution_px() != 0) { total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( this->_internal_horizontal_resolution_px()); } - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; if (this->_internal_vertical_resolution_px() != 0) { total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( this->_internal_vertical_resolution_px()); } + // uint32 lens_id = 9; + if (this->_internal_lens_id() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_lens_id()); + } + + // uint32 definition_file_version = 10; + if (this->_internal_definition_file_version() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_definition_file_version()); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } @@ -12504,12 +12694,19 @@ void Information::MergeImpl(::google::protobuf::Message& to_msg, const ::google: ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + _this->_internal_mutable_camera_cap_flags()->MergeFrom(from._internal_camera_cap_flags()); if (!from._internal_vendor_name().empty()) { _this->_internal_set_vendor_name(from._internal_vendor_name()); } if (!from._internal_model_name().empty()) { _this->_internal_set_model_name(from._internal_model_name()); } + if (!from._internal_firmware_version().empty()) { + _this->_internal_set_firmware_version(from._internal_firmware_version()); + } + if (!from._internal_definition_file_uri().empty()) { + _this->_internal_set_definition_file_uri(from._internal_definition_file_uri()); + } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_focal_length_mm = from._internal_focal_length_mm(); @@ -12540,6 +12737,12 @@ void Information::MergeImpl(::google::protobuf::Message& to_msg, const ::google: if (from._internal_vertical_resolution_px() != 0) { _this->_internal_set_vertical_resolution_px(from._internal_vertical_resolution_px()); } + if (from._internal_lens_id() != 0) { + _this->_internal_set_lens_id(from._internal_lens_id()); + } + if (from._internal_definition_file_version() != 0) { + _this->_internal_set_definition_file_version(from._internal_definition_file_version()); + } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } @@ -12562,11 +12765,14 @@ void Information::InternalSwap(Information* PROTOBUF_RESTRICT other) { auto* arena = GetArena(); ABSL_DCHECK_EQ(arena, other->GetArena()); _internal_metadata_.InternalSwap(&other->_internal_metadata_); + _impl_.camera_cap_flags_.InternalSwap(&other->_impl_.camera_cap_flags_); ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.vendor_name_, &other->_impl_.vendor_name_, arena); ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.model_name_, &other->_impl_.model_name_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.firmware_version_, &other->_impl_.firmware_version_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.definition_file_uri_, &other->_impl_.definition_file_uri_, arena); ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(Information, _impl_.vertical_resolution_px_) - + sizeof(Information::_impl_.vertical_resolution_px_) + PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_version_) + + sizeof(Information::_impl_.definition_file_version_) - PROTOBUF_FIELD_OFFSET(Information, _impl_.focal_length_mm_)>( reinterpret_cast(&_impl_.focal_length_mm_), reinterpret_cast(&other->_impl_.focal_length_mm_)); diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.h b/src/mavsdk_server/src/generated/camera/camera.pb.h index e13e438328..8e069c0d35 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.pb.h @@ -414,6 +414,49 @@ inline bool Status_StorageType_Parse(absl::string_view name, Status_StorageType* return ::google::protobuf::internal::ParseNamedEnum( Status_StorageType_descriptor(), name, value); } +enum Information_CameraCapFlags : int { + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 0, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 1, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_MODES = 2, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 3, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 4, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 5, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 6, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 7, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 8, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 9, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 10, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 11, + Information_CameraCapFlags_Information_CameraCapFlags_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + Information_CameraCapFlags_Information_CameraCapFlags_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool Information_CameraCapFlags_IsValid(int value); +extern const uint32_t Information_CameraCapFlags_internal_data_[]; +constexpr Information_CameraCapFlags Information_CameraCapFlags_CameraCapFlags_MIN = static_cast(0); +constexpr Information_CameraCapFlags Information_CameraCapFlags_CameraCapFlags_MAX = static_cast(11); +constexpr int Information_CameraCapFlags_CameraCapFlags_ARRAYSIZE = 11 + 1; +const ::google::protobuf::EnumDescriptor* +Information_CameraCapFlags_descriptor(); +template +const std::string& Information_CameraCapFlags_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to CameraCapFlags_Name()."); + return Information_CameraCapFlags_Name(static_cast(value)); +} +template <> +inline const std::string& Information_CameraCapFlags_Name(Information_CameraCapFlags value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool Information_CameraCapFlags_Parse(absl::string_view name, Information_CameraCapFlags* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Information_CameraCapFlags_descriptor(), name, value); +} enum Mode : int { MODE_UNKNOWN = 0, MODE_PHOTO = 1, @@ -4818,17 +4861,71 @@ class Information final : // nested types ---------------------------------------------------- + using CameraCapFlags = Information_CameraCapFlags; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_CAPTURE_VIDEO = Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_VIDEO; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_CAPTURE_IMAGE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_IMAGE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_MODES = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_MODES; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_POINT; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS; + static inline bool CameraCapFlags_IsValid(int value) { + return Information_CameraCapFlags_IsValid(value); + } + static constexpr CameraCapFlags CameraCapFlags_MIN = Information_CameraCapFlags_CameraCapFlags_MIN; + static constexpr CameraCapFlags CameraCapFlags_MAX = Information_CameraCapFlags_CameraCapFlags_MAX; + static constexpr int CameraCapFlags_ARRAYSIZE = Information_CameraCapFlags_CameraCapFlags_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* CameraCapFlags_descriptor() { + return Information_CameraCapFlags_descriptor(); + } + template + static inline const std::string& CameraCapFlags_Name(T value) { + return Information_CameraCapFlags_Name(value); + } + static inline bool CameraCapFlags_Parse(absl::string_view name, CameraCapFlags* value) { + return Information_CameraCapFlags_Parse(name, value); + } + // accessors ------------------------------------------------------- enum : int { + kCameraCapFlagsFieldNumber = 12, kVendorNameFieldNumber = 1, kModelNameFieldNumber = 2, - kFocalLengthMmFieldNumber = 3, - kHorizontalSensorSizeMmFieldNumber = 4, - kVerticalSensorSizeMmFieldNumber = 5, - kHorizontalResolutionPxFieldNumber = 6, - kVerticalResolutionPxFieldNumber = 7, + kFirmwareVersionFieldNumber = 3, + kDefinitionFileUriFieldNumber = 11, + kFocalLengthMmFieldNumber = 4, + kHorizontalSensorSizeMmFieldNumber = 5, + kVerticalSensorSizeMmFieldNumber = 6, + kHorizontalResolutionPxFieldNumber = 7, + kVerticalResolutionPxFieldNumber = 8, + kLensIdFieldNumber = 9, + kDefinitionFileVersionFieldNumber = 10, }; + // repeated .mavsdk.rpc.camera.Information.CameraCapFlags camera_cap_flags = 12; + int camera_cap_flags_size() const; + private: + int _internal_camera_cap_flags_size() const; + + public: + void clear_camera_cap_flags() ; + public: + ::mavsdk::rpc::camera::Information_CameraCapFlags camera_cap_flags(int index) const; + void set_camera_cap_flags(int index, ::mavsdk::rpc::camera::Information_CameraCapFlags value); + void add_camera_cap_flags(::mavsdk::rpc::camera::Information_CameraCapFlags value); + const ::google::protobuf::RepeatedField& camera_cap_flags() const; + ::google::protobuf::RepeatedField* mutable_camera_cap_flags(); + + private: + const ::google::protobuf::RepeatedField& _internal_camera_cap_flags() const; + ::google::protobuf::RepeatedField* _internal_mutable_camera_cap_flags(); + + public: // string vendor_name = 1; void clear_vendor_name() ; const std::string& vendor_name() const; @@ -4861,7 +4958,39 @@ class Information final : std::string* _internal_mutable_model_name(); public: - // float focal_length_mm = 3; + // string firmware_version = 3; + void clear_firmware_version() ; + const std::string& firmware_version() const; + template + void set_firmware_version(Arg_&& arg, Args_... args); + std::string* mutable_firmware_version(); + PROTOBUF_NODISCARD std::string* release_firmware_version(); + void set_allocated_firmware_version(std::string* value); + + private: + const std::string& _internal_firmware_version() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_firmware_version( + const std::string& value); + std::string* _internal_mutable_firmware_version(); + + public: + // string definition_file_uri = 11; + void clear_definition_file_uri() ; + const std::string& definition_file_uri() const; + template + void set_definition_file_uri(Arg_&& arg, Args_... args); + std::string* mutable_definition_file_uri(); + PROTOBUF_NODISCARD std::string* release_definition_file_uri(); + void set_allocated_definition_file_uri(std::string* value); + + private: + const std::string& _internal_definition_file_uri() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_definition_file_uri( + const std::string& value); + std::string* _internal_mutable_definition_file_uri(); + + public: + // float focal_length_mm = 4; void clear_focal_length_mm() ; float focal_length_mm() const; void set_focal_length_mm(float value); @@ -4871,7 +5000,7 @@ class Information final : void _internal_set_focal_length_mm(float value); public: - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; void clear_horizontal_sensor_size_mm() ; float horizontal_sensor_size_mm() const; void set_horizontal_sensor_size_mm(float value); @@ -4881,7 +5010,7 @@ class Information final : void _internal_set_horizontal_sensor_size_mm(float value); public: - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; void clear_vertical_sensor_size_mm() ; float vertical_sensor_size_mm() const; void set_vertical_sensor_size_mm(float value); @@ -4891,7 +5020,7 @@ class Information final : void _internal_set_vertical_sensor_size_mm(float value); public: - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; void clear_horizontal_resolution_px() ; ::uint32_t horizontal_resolution_px() const; void set_horizontal_resolution_px(::uint32_t value); @@ -4901,7 +5030,7 @@ class Information final : void _internal_set_horizontal_resolution_px(::uint32_t value); public: - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; void clear_vertical_resolution_px() ; ::uint32_t vertical_resolution_px() const; void set_vertical_resolution_px(::uint32_t value); @@ -4910,6 +5039,26 @@ class Information final : ::uint32_t _internal_vertical_resolution_px() const; void _internal_set_vertical_resolution_px(::uint32_t value); + public: + // uint32 lens_id = 9; + void clear_lens_id() ; + ::uint32_t lens_id() const; + void set_lens_id(::uint32_t value); + + private: + ::uint32_t _internal_lens_id() const; + void _internal_set_lens_id(::uint32_t value); + + public: + // uint32 definition_file_version = 10; + void clear_definition_file_version() ; + ::uint32_t definition_file_version() const; + void set_definition_file_version(::uint32_t value); + + private: + ::uint32_t _internal_definition_file_version() const; + void _internal_set_definition_file_version(::uint32_t value); + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.Information) private: @@ -4917,8 +5066,8 @@ class Information final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 7, 0, - 59, 2> + 4, 12, 0, + 102, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -4934,13 +5083,19 @@ class Information final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::RepeatedField camera_cap_flags_; + mutable ::google::protobuf::internal::CachedSize _camera_cap_flags_cached_byte_size_; ::google::protobuf::internal::ArenaStringPtr vendor_name_; ::google::protobuf::internal::ArenaStringPtr model_name_; + ::google::protobuf::internal::ArenaStringPtr firmware_version_; + ::google::protobuf::internal::ArenaStringPtr definition_file_uri_; float focal_length_mm_; float horizontal_sensor_size_mm_; float vertical_sensor_size_mm_; ::uint32_t horizontal_resolution_px_; ::uint32_t vertical_resolution_px_; + ::uint32_t lens_id_; + ::uint32_t definition_file_version_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -15338,7 +15493,60 @@ inline void Information::set_allocated_model_name(std::string* value) { // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera.Information.model_name) } -// float focal_length_mm = 3; +// string firmware_version = 3; +inline void Information::clear_firmware_version() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.firmware_version_.ClearToEmpty(); +} +inline const std::string& Information::firmware_version() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.Information.firmware_version) + return _internal_firmware_version(); +} +template +inline PROTOBUF_ALWAYS_INLINE void Information::set_firmware_version(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.firmware_version_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.Information.firmware_version) +} +inline std::string* Information::mutable_firmware_version() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_firmware_version(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera.Information.firmware_version) + return _s; +} +inline const std::string& Information::_internal_firmware_version() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.firmware_version_.Get(); +} +inline void Information::_internal_set_firmware_version(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.firmware_version_.Set(value, GetArena()); +} +inline std::string* Information::_internal_mutable_firmware_version() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.firmware_version_.Mutable( GetArena()); +} +inline std::string* Information::release_firmware_version() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera.Information.firmware_version) + return _impl_.firmware_version_.Release(); +} +inline void Information::set_allocated_firmware_version(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.firmware_version_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.firmware_version_.IsDefault()) { + _impl_.firmware_version_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera.Information.firmware_version) +} + +// float focal_length_mm = 4; inline void Information::clear_focal_length_mm() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.focal_length_mm_ = 0; @@ -15361,7 +15569,7 @@ inline void Information::_internal_set_focal_length_mm(float value) { _impl_.focal_length_mm_ = value; } -// float horizontal_sensor_size_mm = 4; +// float horizontal_sensor_size_mm = 5; inline void Information::clear_horizontal_sensor_size_mm() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.horizontal_sensor_size_mm_ = 0; @@ -15384,7 +15592,7 @@ inline void Information::_internal_set_horizontal_sensor_size_mm(float value) { _impl_.horizontal_sensor_size_mm_ = value; } -// float vertical_sensor_size_mm = 5; +// float vertical_sensor_size_mm = 6; inline void Information::clear_vertical_sensor_size_mm() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.vertical_sensor_size_mm_ = 0; @@ -15407,7 +15615,7 @@ inline void Information::_internal_set_vertical_sensor_size_mm(float value) { _impl_.vertical_sensor_size_mm_ = value; } -// uint32 horizontal_resolution_px = 6; +// uint32 horizontal_resolution_px = 7; inline void Information::clear_horizontal_resolution_px() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.horizontal_resolution_px_ = 0u; @@ -15430,7 +15638,7 @@ inline void Information::_internal_set_horizontal_resolution_px(::uint32_t value _impl_.horizontal_resolution_px_ = value; } -// uint32 vertical_resolution_px = 7; +// uint32 vertical_resolution_px = 8; inline void Information::clear_vertical_resolution_px() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.vertical_resolution_px_ = 0u; @@ -15453,6 +15661,149 @@ inline void Information::_internal_set_vertical_resolution_px(::uint32_t value) _impl_.vertical_resolution_px_ = value; } +// uint32 lens_id = 9; +inline void Information::clear_lens_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.lens_id_ = 0u; +} +inline ::uint32_t Information::lens_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.Information.lens_id) + return _internal_lens_id(); +} +inline void Information::set_lens_id(::uint32_t value) { + _internal_set_lens_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.Information.lens_id) +} +inline ::uint32_t Information::_internal_lens_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.lens_id_; +} +inline void Information::_internal_set_lens_id(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.lens_id_ = value; +} + +// uint32 definition_file_version = 10; +inline void Information::clear_definition_file_version() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.definition_file_version_ = 0u; +} +inline ::uint32_t Information::definition_file_version() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.Information.definition_file_version) + return _internal_definition_file_version(); +} +inline void Information::set_definition_file_version(::uint32_t value) { + _internal_set_definition_file_version(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.Information.definition_file_version) +} +inline ::uint32_t Information::_internal_definition_file_version() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.definition_file_version_; +} +inline void Information::_internal_set_definition_file_version(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.definition_file_version_ = value; +} + +// string definition_file_uri = 11; +inline void Information::clear_definition_file_uri() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.definition_file_uri_.ClearToEmpty(); +} +inline const std::string& Information::definition_file_uri() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.Information.definition_file_uri) + return _internal_definition_file_uri(); +} +template +inline PROTOBUF_ALWAYS_INLINE void Information::set_definition_file_uri(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.definition_file_uri_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.Information.definition_file_uri) +} +inline std::string* Information::mutable_definition_file_uri() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_definition_file_uri(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera.Information.definition_file_uri) + return _s; +} +inline const std::string& Information::_internal_definition_file_uri() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.definition_file_uri_.Get(); +} +inline void Information::_internal_set_definition_file_uri(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.definition_file_uri_.Set(value, GetArena()); +} +inline std::string* Information::_internal_mutable_definition_file_uri() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.definition_file_uri_.Mutable( GetArena()); +} +inline std::string* Information::release_definition_file_uri() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera.Information.definition_file_uri) + return _impl_.definition_file_uri_.Release(); +} +inline void Information::set_allocated_definition_file_uri(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.definition_file_uri_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.definition_file_uri_.IsDefault()) { + _impl_.definition_file_uri_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera.Information.definition_file_uri) +} + +// repeated .mavsdk.rpc.camera.Information.CameraCapFlags camera_cap_flags = 12; +inline int Information::_internal_camera_cap_flags_size() const { + return _internal_camera_cap_flags().size(); +} +inline int Information::camera_cap_flags_size() const { + return _internal_camera_cap_flags_size(); +} +inline void Information::clear_camera_cap_flags() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.camera_cap_flags_.Clear(); +} +inline ::mavsdk::rpc::camera::Information_CameraCapFlags Information::camera_cap_flags(int index) const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.Information.camera_cap_flags) + return static_cast<::mavsdk::rpc::camera::Information_CameraCapFlags>(_internal_camera_cap_flags().Get(index)); +} +inline void Information::set_camera_cap_flags(int index, ::mavsdk::rpc::camera::Information_CameraCapFlags value) { + _internal_mutable_camera_cap_flags()->Set(index, value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.Information.camera_cap_flags) +} +inline void Information::add_camera_cap_flags(::mavsdk::rpc::camera::Information_CameraCapFlags value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _internal_mutable_camera_cap_flags()->Add(value); + // @@protoc_insertion_point(field_add:mavsdk.rpc.camera.Information.camera_cap_flags) +} +inline const ::google::protobuf::RepeatedField& Information::camera_cap_flags() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.camera.Information.camera_cap_flags) + return _internal_camera_cap_flags(); +} +inline ::google::protobuf::RepeatedField* Information::mutable_camera_cap_flags() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.camera.Information.camera_cap_flags) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_camera_cap_flags(); +} +inline const ::google::protobuf::RepeatedField& Information::_internal_camera_cap_flags() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.camera_cap_flags_; +} +inline ::google::protobuf::RepeatedField* Information::_internal_mutable_camera_cap_flags() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.camera_cap_flags_; +} + #ifdef __GNUC__ #pragma GCC diagnostic pop #endif // __GNUC__ @@ -15497,6 +15848,12 @@ inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera::Status_Sto return ::mavsdk::rpc::camera::Status_StorageType_descriptor(); } template <> +struct is_proto_enum<::mavsdk::rpc::camera::Information_CameraCapFlags> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera::Information_CameraCapFlags>() { + return ::mavsdk::rpc::camera::Information_CameraCapFlags_descriptor(); +} +template <> struct is_proto_enum<::mavsdk::rpc::camera::Mode> : std::true_type {}; template <> inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera::Mode>() { diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 59bda93a26..04308992d4 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -547,7 +547,9 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr Information::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : vendor_name_( + : camera_cap_flags_{}, + _camera_cap_flags_cached_byte_size_{0}, + vendor_name_( &::google::protobuf::internal::fixed_address_empty_string, ::_pbi::ConstantInitialized()), model_name_( @@ -1062,7 +1064,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace rpc } // namespace mavsdk static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[55]; -static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[9]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[10]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( @@ -1513,6 +1515,7 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.lens_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.definition_file_version_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.definition_file_uri_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.camera_cap_flags_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreamSettings, _internal_metadata_), ~0u, // no _extensions_ @@ -1679,14 +1682,14 @@ static const ::_pbi::MigrationSchema {408, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsRequest)}, {417, 426, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsResponse)}, {427, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - {446, -1, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreamSettings)}, - {461, 473, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreamInfo)}, - {477, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - {489, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - {501, 515, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - {521, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, - {531, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, - {547, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, + {447, -1, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreamSettings)}, + {462, 474, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreamInfo)}, + {478, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + {490, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + {502, 516, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + {522, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + {532, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, + {548, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -1840,7 +1843,7 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "\030\001 \001(\0162(.mavsdk.rpc.camera_server.Camera" "Feedback\"j\n\034RespondResetSettingsResponse" "\022J\n\024camera_server_result\030\001 \001(\0132,.mavsdk." - "rpc.camera_server.CameraServerResult\"\276\002\n" + "rpc.camera_server.CameraServerResult\"\227\007\n" "\013Information\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmod" "el_name\030\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022" "\027\n\017focal_length_mm\030\004 \001(\002\022!\n\031horizontal_s" @@ -1848,157 +1851,172 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "ize_mm\030\006 \001(\002\022 \n\030horizontal_resolution_px" "\030\007 \001(\r\022\036\n\026vertical_resolution_px\030\010 \001(\r\022\017" "\n\007lens_id\030\t \001(\r\022\037\n\027definition_file_versi" - "on\030\n \001(\r\022\033\n\023definition_file_uri\030\013 \001(\t\"\305\001" - "\n\023VideoStreamSettings\022\025\n\rframe_rate_hz\030\001" - " \001(\002\022!\n\031horizontal_resolution_pix\030\002 \001(\r\022" - "\037\n\027vertical_resolution_pix\030\003 \001(\r\022\024\n\014bit_" - "rate_b_s\030\004 \001(\r\022\024\n\014rotation_deg\030\005 \001(\r\022\013\n\003" - "uri\030\006 \001(\t\022\032\n\022horizontal_fov_deg\030\007 \001(\002\"\352\003" - "\n\017VideoStreamInfo\022\021\n\tstream_id\030\001 \001(\005\022\?\n\010" - "settings\030\002 \001(\0132-.mavsdk.rpc.camera_serve" - "r.VideoStreamSettings\022K\n\006status\030\003 \001(\0162;." + "on\030\n \001(\r\022\033\n\023definition_file_uri\030\013 \001(\t\022N\n" + "\020camera_cap_flags\030\014 \003(\01624.mavsdk.rpc.cam" + "era_server.Information.CameraCapFlags\"\206\004" + "\n\016CameraCapFlags\022\"\n\036CAMERA_CAP_FLAGS_CAP" + "TURE_VIDEO\020\000\022\"\n\036CAMERA_CAP_FLAGS_CAPTURE" + "_IMAGE\020\001\022\036\n\032CAMERA_CAP_FLAGS_HAS_MODES\020\002" + "\0224\n0CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_I" + "N_VIDEO_MODE\020\003\0224\n0CAMERA_CAP_FLAGS_CAN_C" + "APTURE_VIDEO_IN_IMAGE_MODE\020\004\022*\n&CAMERA_C" + "AP_FLAGS_HAS_IMAGE_SURVEY_MODE\020\005\022#\n\037CAME" + "RA_CAP_FLAGS_HAS_BASIC_ZOOM\020\006\022$\n CAMERA_" + "CAP_FLAGS_HAS_BASIC_FOCUS\020\007\022%\n!CAMERA_CA" + "P_FLAGS_HAS_VIDEO_STREAM\020\010\022\'\n#CAMERA_CAP" + "_FLAGS_HAS_TRACKING_POINT\020\t\022+\n\'CAMERA_CA" + "P_FLAGS_HAS_TRACKING_RECTANGLE\020\n\022,\n(CAME" + "RA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS\020\013\"\305" + "\001\n\023VideoStreamSettings\022\025\n\rframe_rate_hz\030" + "\001 \001(\002\022!\n\031horizontal_resolution_pix\030\002 \001(\r" + "\022\037\n\027vertical_resolution_pix\030\003 \001(\r\022\024\n\014bit" + "_rate_b_s\030\004 \001(\r\022\024\n\014rotation_deg\030\005 \001(\r\022\013\n" + "\003uri\030\006 \001(\t\022\032\n\022horizontal_fov_deg\030\007 \001(\002\"\352" + "\003\n\017VideoStreamInfo\022\021\n\tstream_id\030\001 \001(\005\022\?\n" + "\010settings\030\002 \001(\0132-.mavsdk.rpc.camera_serv" + "er.VideoStreamSettings\022K\n\006status\030\003 \001(\0162;" + ".mavsdk.rpc.camera_server.VideoStreamInf" + "o.VideoStreamStatus\022O\n\010spectrum\030\004 \001(\0162=." "mavsdk.rpc.camera_server.VideoStreamInfo" - ".VideoStreamStatus\022O\n\010spectrum\030\004 \001(\0162=.m" - "avsdk.rpc.camera_server.VideoStreamInfo." - "VideoStreamSpectrum\"]\n\021VideoStreamStatus" - "\022#\n\037VIDEO_STREAM_STATUS_NOT_RUNNING\020\000\022#\n" - "\037VIDEO_STREAM_STATUS_IN_PROGRESS\020\001\"\205\001\n\023V" - "ideoStreamSpectrum\022!\n\035VIDEO_STREAM_SPECT" - "RUM_UNKNOWN\020\000\022\'\n#VIDEO_STREAM_SPECTRUM_V" - "ISIBLE_LIGHT\020\001\022\"\n\036VIDEO_STREAM_SPECTRUM_" - "INFRARED\020\002\"q\n\010Position\022\024\n\014latitude_deg\030\001" - " \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_" - "altitude_m\030\003 \001(\002\022\033\n\023relative_altitude_m\030" - "\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(" - "\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\022" - "4\n\010position\030\001 \001(\0132\".mavsdk.rpc.camera_se" - "rver.Position\022A\n\023attitude_quaternion\030\002 \001" - "(\0132$.mavsdk.rpc.camera_server.Quaternion" - "\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(" - "\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022C" - "ameraServerResult\022C\n\006result\030\001 \001(\01623.mavs" - "dk.rpc.camera_server.CameraServerResult." - "Result\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n" - "\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n" - "\022RESULT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021" - "\n\rRESULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016R" - "ESULT_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT" - "\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010\"\214\005\n\022StorageInfo" - "rmation\022\030\n\020used_storage_mib\030\001 \001(\002\022\035\n\025ava" - "ilable_storage_mib\030\002 \001(\002\022\031\n\021total_storag" - "e_mib\030\003 \001(\002\022R\n\016storage_status\030\004 \001(\0162:.ma" - "vsdk.rpc.camera_server.StorageInformatio" - "n.StorageStatus\022\022\n\nstorage_id\030\005 \001(\r\022N\n\014s" - "torage_type\030\006 \001(\01628.mavsdk.rpc.camera_se" - "rver.StorageInformation.StorageType\022\030\n\020r" - "ead_speed_mib_s\030\007 \001(\002\022\031\n\021write_speed_mib" - "_s\030\010 \001(\002\"\221\001\n\rStorageStatus\022 \n\034STORAGE_ST" - "ATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS_U" - "NFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATTED" - "\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240\001\n" - "\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000\022\032" - "\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_TY" - "PE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017STO" - "RAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376\001\"" - "\356\003\n\rCaptureStatus\022\030\n\020image_interval_s\030\001 " - "\001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\036\n\026availab" - "le_capacity_mib\030\003 \001(\002\022I\n\014image_status\030\004 " - "\001(\01623.mavsdk.rpc.camera_server.CaptureSt" - "atus.ImageStatus\022I\n\014video_status\030\005 \001(\01623" - ".mavsdk.rpc.camera_server.CaptureStatus." - "VideoStatus\022\023\n\013image_count\030\006 \001(\005\"\221\001\n\013Ima" - "geStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$\n IMAGE" - "_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032IMAGE_S" - "TATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_STATUS_IN" - "TERVAL_IN_PROGRESS\020\003\"J\n\013VideoStatus\022\025\n\021V" - "IDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATUS_CAPTU" - "RE_IN_PROGRESS\020\001*{\n\016CameraFeedback\022\033\n\027CA" - "MERA_FEEDBACK_UNKNOWN\020\000\022\026\n\022CAMERA_FEEDBA" - "CK_OK\020\001\022\030\n\024CAMERA_FEEDBACK_BUSY\020\002\022\032\n\026CAM" - "ERA_FEEDBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_UN" - "KNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\0022" - "\222\031\n\023CameraServerService\022y\n\016SetInformatio" - "n\022/.mavsdk.rpc.camera_server.SetInformat" - "ionRequest\0320.mavsdk.rpc.camera_server.Se" - "tInformationResponse\"\004\200\265\030\001\022\205\001\n\022SetVideoS" - "treamInfo\0223.mavsdk.rpc.camera_server.Set" - "VideoStreamInfoRequest\0324.mavsdk.rpc.came" - "ra_server.SetVideoStreamInfoResponse\"\004\200\265" - "\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.camera_" - "server.SetInProgressRequest\032/.mavsdk.rpc" - ".camera_server.SetInProgressResponse\"\004\200\265" - "\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rpc.ca" - "mera_server.SubscribeTakePhotoRequest\032+." - "mavsdk.rpc.camera_server.TakePhotoRespon" - "se\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk." - "rpc.camera_server.RespondTakePhotoReques" - "t\0322.mavsdk.rpc.camera_server.RespondTake" - "PhotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVi" - "deo\0224.mavsdk.rpc.camera_server.Subscribe" - "StartVideoRequest\032,.mavsdk.rpc.camera_se" - "rver.StartVideoResponse\"\004\200\265\030\0000\001\022\202\001\n\021Resp" - "ondStartVideo\0222.mavsdk.rpc.camera_server" - ".RespondStartVideoRequest\0323.mavsdk.rpc.c" - "amera_server.RespondStartVideoResponse\"\004" - "\200\265\030\001\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc." - "camera_server.SubscribeStopVideoRequest\032" - "+.mavsdk.rpc.camera_server.StopVideoResp" - "onse\"\004\200\265\030\0000\001\022\177\n\020RespondStopVideo\0221.mavsd" - "k.rpc.camera_server.RespondStopVideoRequ" - "est\0322.mavsdk.rpc.camera_server.RespondSt" - "opVideoResponse\"\004\200\265\030\001\022\234\001\n\034SubscribeStart" - "VideoStreaming\022=.mavsdk.rpc.camera_serve" - "r.SubscribeStartVideoStreamingRequest\0325." - "mavsdk.rpc.camera_server.StartVideoStrea" - "mingResponse\"\004\200\265\030\0000\001\022\235\001\n\032RespondStartVid" - "eoStreaming\022;.mavsdk.rpc.camera_server.R" - "espondStartVideoStreamingRequest\032<.mavsd" - "k.rpc.camera_server.RespondStartVideoStr" - "eamingResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStopVi" - "deoStreaming\022<.mavsdk.rpc.camera_server." - "SubscribeStopVideoStreamingRequest\0324.mav" - "sdk.rpc.camera_server.StopVideoStreaming" - "Response\"\004\200\265\030\0000\001\022\232\001\n\031RespondStopVideoStr" - "eaming\022:.mavsdk.rpc.camera_server.Respon" - "dStopVideoStreamingRequest\032;.mavsdk.rpc." - "camera_server.RespondStopVideoStreamingR" - "esponse\"\004\200\265\030\001\022x\n\020SubscribeSetMode\0221.mavs" - "dk.rpc.camera_server.SubscribeSetModeReq" - "uest\032).mavsdk.rpc.camera_server.SetModeR" - "esponse\"\004\200\265\030\0000\001\022y\n\016RespondSetMode\022/.mavs" - "dk.rpc.camera_server.RespondSetModeReque" - "st\0320.mavsdk.rpc.camera_server.RespondSet" - "ModeResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStorageI" - "nformation\022<.mavsdk.rpc.camera_server.Su" - "bscribeStorageInformationRequest\0324.mavsd" - "k.rpc.camera_server.StorageInformationRe" - "sponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInforma" - "tion\022:.mavsdk.rpc.camera_server.RespondS" - "torageInformationRequest\032;.mavsdk.rpc.ca" - "mera_server.RespondStorageInformationRes" - "ponse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\0227" - ".mavsdk.rpc.camera_server.SubscribeCaptu" - "reStatusRequest\032/.mavsdk.rpc.camera_serv" - "er.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024Res" - "pondCaptureStatus\0225.mavsdk.rpc.camera_se" - "rver.RespondCaptureStatusRequest\0326.mavsd" - "k.rpc.camera_server.RespondCaptureStatus" - "Response\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatStorag" - "e\0227.mavsdk.rpc.camera_server.SubscribeFo" - "rmatStorageRequest\032/.mavsdk.rpc.camera_s" - "erver.FormatStorageResponse\"\004\200\265\030\0000\001\022\213\001\n\024" - "RespondFormatStorage\0225.mavsdk.rpc.camera" - "_server.RespondFormatStorageRequest\0326.ma" - "vsdk.rpc.camera_server.RespondFormatStor" - "ageResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeResetSett" - "ings\0227.mavsdk.rpc.camera_server.Subscrib" - "eResetSettingsRequest\032/.mavsdk.rpc.camer" - "a_server.ResetSettingsResponse\"\004\200\265\030\0000\001\022\213" - "\001\n\024RespondResetSettings\0225.mavsdk.rpc.cam" - "era_server.RespondResetSettingsRequest\0326" - ".mavsdk.rpc.camera_server.RespondResetSe" - "ttingsResponse\"\004\200\265\030\001B,\n\027io.mavsdk.camera" - "_serverB\021CameraServerProtob\006proto3" + ".VideoStreamSpectrum\"]\n\021VideoStreamStatu" + "s\022#\n\037VIDEO_STREAM_STATUS_NOT_RUNNING\020\000\022#" + "\n\037VIDEO_STREAM_STATUS_IN_PROGRESS\020\001\"\205\001\n\023" + "VideoStreamSpectrum\022!\n\035VIDEO_STREAM_SPEC" + "TRUM_UNKNOWN\020\000\022\'\n#VIDEO_STREAM_SPECTRUM_" + "VISIBLE_LIGHT\020\001\022\"\n\036VIDEO_STREAM_SPECTRUM" + "_INFRARED\020\002\"q\n\010Position\022\024\n\014latitude_deg\030" + "\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute" + "_altitude_m\030\003 \001(\002\022\033\n\023relative_altitude_m" + "\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001" + "(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo" + "\0224\n\010position\030\001 \001(\0132\".mavsdk.rpc.camera_s" + "erver.Position\022A\n\023attitude_quaternion\030\002 " + "\001(\0132$.mavsdk.rpc.camera_server.Quaternio" + "n\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001" + "(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022" + "CameraServerResult\022C\n\006result\030\001 \001(\01623.mav" + "sdk.rpc.camera_server.CameraServerResult" + ".Result\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022" + "\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026" + "\n\022RESULT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022" + "\021\n\rRESULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016" + "RESULT_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMEN" + "T\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010\"\214\005\n\022StorageInf" + "ormation\022\030\n\020used_storage_mib\030\001 \001(\002\022\035\n\025av" + "ailable_storage_mib\030\002 \001(\002\022\031\n\021total_stora" + "ge_mib\030\003 \001(\002\022R\n\016storage_status\030\004 \001(\0162:.m" + "avsdk.rpc.camera_server.StorageInformati" + "on.StorageStatus\022\022\n\nstorage_id\030\005 \001(\r\022N\n\014" + "storage_type\030\006 \001(\01628.mavsdk.rpc.camera_s" + "erver.StorageInformation.StorageType\022\030\n\020" + "read_speed_mib_s\030\007 \001(\002\022\031\n\021write_speed_mi" + "b_s\030\010 \001(\002\"\221\001\n\rStorageStatus\022 \n\034STORAGE_S" + "TATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS_" + "UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATTE" + "D\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240\001" + "\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000\022" + "\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_T" + "YPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017ST" + "ORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376\001" + "\"\356\003\n\rCaptureStatus\022\030\n\020image_interval_s\030\001" + " \001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\036\n\026availa" + "ble_capacity_mib\030\003 \001(\002\022I\n\014image_status\030\004" + " \001(\01623.mavsdk.rpc.camera_server.CaptureS" + "tatus.ImageStatus\022I\n\014video_status\030\005 \001(\0162" + "3.mavsdk.rpc.camera_server.CaptureStatus" + ".VideoStatus\022\023\n\013image_count\030\006 \001(\005\"\221\001\n\013Im" + "ageStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$\n IMAG" + "E_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032IMAGE_" + "STATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_STATUS_I" + "NTERVAL_IN_PROGRESS\020\003\"J\n\013VideoStatus\022\025\n\021" + "VIDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATUS_CAPT" + "URE_IN_PROGRESS\020\001*{\n\016CameraFeedback\022\033\n\027C" + "AMERA_FEEDBACK_UNKNOWN\020\000\022\026\n\022CAMERA_FEEDB" + "ACK_OK\020\001\022\030\n\024CAMERA_FEEDBACK_BUSY\020\002\022\032\n\026CA" + "MERA_FEEDBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_U" + "NKNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\002" + "2\222\031\n\023CameraServerService\022y\n\016SetInformati" + "on\022/.mavsdk.rpc.camera_server.SetInforma" + "tionRequest\0320.mavsdk.rpc.camera_server.S" + "etInformationResponse\"\004\200\265\030\001\022\205\001\n\022SetVideo" + "StreamInfo\0223.mavsdk.rpc.camera_server.Se" + "tVideoStreamInfoRequest\0324.mavsdk.rpc.cam" + "era_server.SetVideoStreamInfoResponse\"\004\200" + "\265\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.camera" + "_server.SetInProgressRequest\032/.mavsdk.rp" + "c.camera_server.SetInProgressResponse\"\004\200" + "\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rpc.c" + "amera_server.SubscribeTakePhotoRequest\032+" + ".mavsdk.rpc.camera_server.TakePhotoRespo" + "nse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk" + ".rpc.camera_server.RespondTakePhotoReque" + "st\0322.mavsdk.rpc.camera_server.RespondTak" + "ePhotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartV" + "ideo\0224.mavsdk.rpc.camera_server.Subscrib" + "eStartVideoRequest\032,.mavsdk.rpc.camera_s" + "erver.StartVideoResponse\"\004\200\265\030\0000\001\022\202\001\n\021Res" + "pondStartVideo\0222.mavsdk.rpc.camera_serve" + "r.RespondStartVideoRequest\0323.mavsdk.rpc." + "camera_server.RespondStartVideoResponse\"" + "\004\200\265\030\001\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc" + ".camera_server.SubscribeStopVideoRequest" + "\032+.mavsdk.rpc.camera_server.StopVideoRes" + "ponse\"\004\200\265\030\0000\001\022\177\n\020RespondStopVideo\0221.mavs" + "dk.rpc.camera_server.RespondStopVideoReq" + "uest\0322.mavsdk.rpc.camera_server.RespondS" + "topVideoResponse\"\004\200\265\030\001\022\234\001\n\034SubscribeStar" + "tVideoStreaming\022=.mavsdk.rpc.camera_serv" + "er.SubscribeStartVideoStreamingRequest\0325" + ".mavsdk.rpc.camera_server.StartVideoStre" + "amingResponse\"\004\200\265\030\0000\001\022\235\001\n\032RespondStartVi" + "deoStreaming\022;.mavsdk.rpc.camera_server." + "RespondStartVideoStreamingRequest\032<.mavs" + "dk.rpc.camera_server.RespondStartVideoSt" + "reamingResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStopV" + "ideoStreaming\022<.mavsdk.rpc.camera_server" + ".SubscribeStopVideoStreamingRequest\0324.ma" + "vsdk.rpc.camera_server.StopVideoStreamin" + "gResponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStopVideoSt" + "reaming\022:.mavsdk.rpc.camera_server.Respo" + "ndStopVideoStreamingRequest\032;.mavsdk.rpc" + ".camera_server.RespondStopVideoStreaming" + "Response\"\004\200\265\030\001\022x\n\020SubscribeSetMode\0221.mav" + "sdk.rpc.camera_server.SubscribeSetModeRe" + "quest\032).mavsdk.rpc.camera_server.SetMode" + "Response\"\004\200\265\030\0000\001\022y\n\016RespondSetMode\022/.mav" + "sdk.rpc.camera_server.RespondSetModeRequ" + "est\0320.mavsdk.rpc.camera_server.RespondSe" + "tModeResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStorage" + "Information\022<.mavsdk.rpc.camera_server.S" + "ubscribeStorageInformationRequest\0324.mavs" + "dk.rpc.camera_server.StorageInformationR" + "esponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInform" + "ation\022:.mavsdk.rpc.camera_server.Respond" + "StorageInformationRequest\032;.mavsdk.rpc.c" + "amera_server.RespondStorageInformationRe" + "sponse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\022" + "7.mavsdk.rpc.camera_server.SubscribeCapt" + "ureStatusRequest\032/.mavsdk.rpc.camera_ser" + "ver.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024Re" + "spondCaptureStatus\0225.mavsdk.rpc.camera_s" + "erver.RespondCaptureStatusRequest\0326.mavs" + "dk.rpc.camera_server.RespondCaptureStatu" + "sResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatStora" + "ge\0227.mavsdk.rpc.camera_server.SubscribeF" + "ormatStorageRequest\032/.mavsdk.rpc.camera_" + "server.FormatStorageResponse\"\004\200\265\030\0000\001\022\213\001\n" + "\024RespondFormatStorage\0225.mavsdk.rpc.camer" + "a_server.RespondFormatStorageRequest\0326.m" + "avsdk.rpc.camera_server.RespondFormatSto" + "rageResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeResetSet" + "tings\0227.mavsdk.rpc.camera_server.Subscri" + "beResetSettingsRequest\032/.mavsdk.rpc.came" + "ra_server.ResetSettingsResponse\"\004\200\265\030\0000\001\022" + "\213\001\n\024RespondResetSettings\0225.mavsdk.rpc.ca" + "mera_server.RespondResetSettingsRequest\032" + "6.mavsdk.rpc.camera_server.RespondResetS" + "ettingsResponse\"\004\200\265\030\001B,\n\027io.mavsdk.camer" + "a_serverB\021CameraServerProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -2008,7 +2026,7 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 10074, + 10675, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, @@ -2043,10 +2061,40 @@ static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_camera_5fserver_2fcamera_ namespace mavsdk { namespace rpc { namespace camera_server { -const ::google::protobuf::EnumDescriptor* VideoStreamInfo_VideoStreamStatus_descriptor() { +const ::google::protobuf::EnumDescriptor* Information_CameraCapFlags_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[0]; } +PROTOBUF_CONSTINIT const uint32_t Information_CameraCapFlags_internal_data_[] = { + 786432u, 0u, }; +bool Information_CameraCapFlags_IsValid(int value) { + return 0 <= value && value <= 11; +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_CAPTURE_VIDEO; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_CAPTURE_IMAGE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_MODES; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE; +constexpr Information_CameraCapFlags Information::CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS; +constexpr Information_CameraCapFlags Information::CameraCapFlags_MIN; +constexpr Information_CameraCapFlags Information::CameraCapFlags_MAX; +constexpr int Information::CameraCapFlags_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::google::protobuf::EnumDescriptor* VideoStreamInfo_VideoStreamStatus_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[1]; +} PROTOBUF_CONSTINIT const uint32_t VideoStreamInfo_VideoStreamStatus_internal_data_[] = { 131072u, 0u, }; bool VideoStreamInfo_VideoStreamStatus_IsValid(int value) { @@ -2065,7 +2113,7 @@ constexpr int VideoStreamInfo::VideoStreamStatus_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* VideoStreamInfo_VideoStreamSpectrum_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[1]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; } PROTOBUF_CONSTINIT const uint32_t VideoStreamInfo_VideoStreamSpectrum_internal_data_[] = { 196608u, 0u, }; @@ -2086,7 +2134,7 @@ constexpr int VideoStreamInfo::VideoStreamSpectrum_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* CameraServerResult_Result_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[3]; } PROTOBUF_CONSTINIT const uint32_t CameraServerResult_Result_internal_data_[] = { 589824u, 0u, }; @@ -2113,7 +2161,7 @@ constexpr int CameraServerResult::Result_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* StorageInformation_StorageStatus_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[3]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[4]; } PROTOBUF_CONSTINIT const uint32_t StorageInformation_StorageStatus_internal_data_[] = { 262144u, 0u, }; @@ -2135,7 +2183,7 @@ constexpr int StorageInformation::StorageStatus_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* StorageInformation_StorageType_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[4]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[5]; } PROTOBUF_CONSTINIT const uint32_t StorageInformation_StorageType_internal_data_[] = { 262144u, 65568u, 8u, 254u, }; @@ -2159,7 +2207,7 @@ constexpr int StorageInformation::StorageType_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* CaptureStatus_ImageStatus_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[5]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[6]; } PROTOBUF_CONSTINIT const uint32_t CaptureStatus_ImageStatus_internal_data_[] = { 262144u, 0u, }; @@ -2181,7 +2229,7 @@ constexpr int CaptureStatus::ImageStatus_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* CaptureStatus_VideoStatus_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[6]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; } PROTOBUF_CONSTINIT const uint32_t CaptureStatus_VideoStatus_internal_data_[] = { 131072u, 0u, }; @@ -2201,7 +2249,7 @@ constexpr int CaptureStatus::VideoStatus_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) const ::google::protobuf::EnumDescriptor* CameraFeedback_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[8]; } PROTOBUF_CONSTINIT const uint32_t CameraFeedback_internal_data_[] = { 262144u, 0u, }; @@ -2210,7 +2258,7 @@ bool CameraFeedback_IsValid(int value) { } const ::google::protobuf::EnumDescriptor* Mode_descriptor() { ::google::protobuf::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[8]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[9]; } PROTOBUF_CONSTINIT const uint32_t Mode_internal_data_[] = { 196608u, 0u, }; @@ -9444,7 +9492,9 @@ Information::Information(::google::protobuf::Arena* arena) inline PROTOBUF_NDEBUG_INLINE Information::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) - : vendor_name_(arena, from.vendor_name_), + : camera_cap_flags_{visibility, arena, from.camera_cap_flags_}, + _camera_cap_flags_cached_byte_size_{0}, + vendor_name_(arena, from.vendor_name_), model_name_(arena, from.model_name_), firmware_version_(arena, from.firmware_version_), definition_file_uri_(arena, from.definition_file_uri_), @@ -9472,7 +9522,9 @@ Information::Information( inline PROTOBUF_NDEBUG_INLINE Information::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : vendor_name_(arena), + : camera_cap_flags_{visibility, arena}, + _camera_cap_flags_cached_byte_size_{0}, + vendor_name_(arena), model_name_(arena), firmware_version_(arena), definition_file_uri_(arena), @@ -9508,6 +9560,7 @@ PROTOBUF_NOINLINE void Information::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; + _impl_.camera_cap_flags_.Clear(); _impl_.vendor_name_.ClearToEmpty(); _impl_.model_name_.ClearToEmpty(); _impl_.firmware_version_.ClearToEmpty(); @@ -9526,15 +9579,15 @@ const char* Information::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<4, 11, 0, 109, 2> Information::_table_ = { +const ::_pbi::TcParseTable<4, 12, 0, 109, 2> Information::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 11, 120, // max_field_number, fast_idx_mask + 12, 120, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294965248, // skipmap + 4294963200, // skipmap offsetof(decltype(_table_), field_entries), - 11, // num_field_entries + 12, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_Information_default_instance_._instance, @@ -9574,7 +9627,9 @@ const ::_pbi::TcParseTable<4, 11, 0, 109, 2> Information::_table_ = { // string definition_file_uri = 11; {::_pbi::TcParser::FastUS1, {90, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_uri_)}}, - {::_pbi::TcParser::MiniParse, {}}, + // repeated .mavsdk.rpc.camera_server.Information.CameraCapFlags camera_cap_flags = 12; + {::_pbi::TcParser::FastV32P1, + {98, 63, 0, PROTOBUF_FIELD_OFFSET(Information, _impl_.camera_cap_flags_)}}, {::_pbi::TcParser::MiniParse, {}}, {::_pbi::TcParser::MiniParse, {}}, {::_pbi::TcParser::MiniParse, {}}, @@ -9614,6 +9669,9 @@ const ::_pbi::TcParseTable<4, 11, 0, 109, 2> Information::_table_ = { // string definition_file_uri = 11; {PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_uri_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // repeated .mavsdk.rpc.camera_server.Information.CameraCapFlags camera_cap_flags = 12; + {PROTOBUF_FIELD_OFFSET(Information, _impl_.camera_cap_flags_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kPackedOpenEnum)}, }}, // no aux_entries {{ @@ -9729,6 +9787,15 @@ ::uint8_t* Information::_InternalSerialize( target = stream->WriteStringMaybeAliased(11, _s, target); } + // repeated .mavsdk.rpc.camera_server.Information.CameraCapFlags camera_cap_flags = 12; + { + std::size_t byte_size = _impl_._camera_cap_flags_cached_byte_size_.Get(); + if (byte_size > 0) { + target = stream->WriteEnumPacked(12, _internal_camera_cap_flags(), + byte_size, target); + } + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( @@ -9746,6 +9813,23 @@ ::size_t Information::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; + // repeated .mavsdk.rpc.camera_server.Information.CameraCapFlags camera_cap_flags = 12; + { + std::size_t data_size = 0; + auto count = static_cast(this->_internal_camera_cap_flags_size()); + + for (std::size_t i = 0; i < count; ++i) { + data_size += ::_pbi::WireFormatLite::EnumSize( + this->_internal_camera_cap_flags().Get(static_cast(i))); + } + total_size += data_size; + if (data_size > 0) { + total_size += 1; + total_size += ::_pbi::WireFormatLite::Int32Size( + static_cast(data_size)); + } + _impl_._camera_cap_flags_cached_byte_size_.Set(::_pbi::ToCachedSize(data_size)); + } // string vendor_name = 1; if (!this->_internal_vendor_name().empty()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( @@ -9843,6 +9927,7 @@ void Information::MergeImpl(::google::protobuf::Message& to_msg, const ::google: ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + _this->_internal_mutable_camera_cap_flags()->MergeFrom(from._internal_camera_cap_flags()); if (!from._internal_vendor_name().empty()) { _this->_internal_set_vendor_name(from._internal_vendor_name()); } @@ -9913,6 +9998,7 @@ void Information::InternalSwap(Information* PROTOBUF_RESTRICT other) { auto* arena = GetArena(); ABSL_DCHECK_EQ(arena, other->GetArena()); _internal_metadata_.InternalSwap(&other->_internal_metadata_); + _impl_.camera_cap_flags_.InternalSwap(&other->_impl_.camera_cap_flags_); ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.vendor_name_, &other->_impl_.vendor_name_, arena); ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.model_name_, &other->_impl_.model_name_, arena); ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.firmware_version_, &other->_impl_.firmware_version_, arena); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index f1ce4a445f..e39c70b199 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -237,6 +237,49 @@ namespace protobuf { namespace mavsdk { namespace rpc { namespace camera_server { +enum Information_CameraCapFlags : int { + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 0, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 1, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_MODES = 2, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 3, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 4, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 5, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 6, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 7, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 8, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 9, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 10, + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 11, + Information_CameraCapFlags_Information_CameraCapFlags_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + Information_CameraCapFlags_Information_CameraCapFlags_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool Information_CameraCapFlags_IsValid(int value); +extern const uint32_t Information_CameraCapFlags_internal_data_[]; +constexpr Information_CameraCapFlags Information_CameraCapFlags_CameraCapFlags_MIN = static_cast(0); +constexpr Information_CameraCapFlags Information_CameraCapFlags_CameraCapFlags_MAX = static_cast(11); +constexpr int Information_CameraCapFlags_CameraCapFlags_ARRAYSIZE = 11 + 1; +const ::google::protobuf::EnumDescriptor* +Information_CameraCapFlags_descriptor(); +template +const std::string& Information_CameraCapFlags_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to CameraCapFlags_Name()."); + return Information_CameraCapFlags_Name(static_cast(value)); +} +template <> +inline const std::string& Information_CameraCapFlags_Name(Information_CameraCapFlags value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool Information_CameraCapFlags_Parse(absl::string_view name, Information_CameraCapFlags* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Information_CameraCapFlags_descriptor(), name, value); +} enum VideoStreamInfo_VideoStreamStatus : int { VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_NOT_RUNNING = 0, VideoStreamInfo_VideoStreamStatus_VIDEO_STREAM_STATUS_IN_PROGRESS = 1, @@ -5822,9 +5865,40 @@ class Information final : // nested types ---------------------------------------------------- + using CameraCapFlags = Information_CameraCapFlags; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_CAPTURE_VIDEO = Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_VIDEO; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_CAPTURE_IMAGE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_IMAGE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_MODES = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_MODES; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_POINT; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE; + static constexpr CameraCapFlags CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS; + static inline bool CameraCapFlags_IsValid(int value) { + return Information_CameraCapFlags_IsValid(value); + } + static constexpr CameraCapFlags CameraCapFlags_MIN = Information_CameraCapFlags_CameraCapFlags_MIN; + static constexpr CameraCapFlags CameraCapFlags_MAX = Information_CameraCapFlags_CameraCapFlags_MAX; + static constexpr int CameraCapFlags_ARRAYSIZE = Information_CameraCapFlags_CameraCapFlags_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* CameraCapFlags_descriptor() { + return Information_CameraCapFlags_descriptor(); + } + template + static inline const std::string& CameraCapFlags_Name(T value) { + return Information_CameraCapFlags_Name(value); + } + static inline bool CameraCapFlags_Parse(absl::string_view name, CameraCapFlags* value) { + return Information_CameraCapFlags_Parse(name, value); + } + // accessors ------------------------------------------------------- enum : int { + kCameraCapFlagsFieldNumber = 12, kVendorNameFieldNumber = 1, kModelNameFieldNumber = 2, kFirmwareVersionFieldNumber = 3, @@ -5837,6 +5911,25 @@ class Information final : kLensIdFieldNumber = 9, kDefinitionFileVersionFieldNumber = 10, }; + // repeated .mavsdk.rpc.camera_server.Information.CameraCapFlags camera_cap_flags = 12; + int camera_cap_flags_size() const; + private: + int _internal_camera_cap_flags_size() const; + + public: + void clear_camera_cap_flags() ; + public: + ::mavsdk::rpc::camera_server::Information_CameraCapFlags camera_cap_flags(int index) const; + void set_camera_cap_flags(int index, ::mavsdk::rpc::camera_server::Information_CameraCapFlags value); + void add_camera_cap_flags(::mavsdk::rpc::camera_server::Information_CameraCapFlags value); + const ::google::protobuf::RepeatedField& camera_cap_flags() const; + ::google::protobuf::RepeatedField* mutable_camera_cap_flags(); + + private: + const ::google::protobuf::RepeatedField& _internal_camera_cap_flags() const; + ::google::protobuf::RepeatedField* _internal_mutable_camera_cap_flags(); + + public: // string vendor_name = 1; void clear_vendor_name() ; const std::string& vendor_name() const; @@ -5977,7 +6070,7 @@ class Information final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 4, 11, 0, + 4, 12, 0, 109, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -5994,6 +6087,8 @@ class Information final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::RepeatedField camera_cap_flags_; + mutable ::google::protobuf::internal::CachedSize _camera_cap_flags_cached_byte_size_; ::google::protobuf::internal::ArenaStringPtr vendor_name_; ::google::protobuf::internal::ArenaStringPtr model_name_; ::google::protobuf::internal::ArenaStringPtr firmware_version_; @@ -13402,6 +13497,50 @@ inline void Information::set_allocated_definition_file_uri(std::string* value) { // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.definition_file_uri) } +// repeated .mavsdk.rpc.camera_server.Information.CameraCapFlags camera_cap_flags = 12; +inline int Information::_internal_camera_cap_flags_size() const { + return _internal_camera_cap_flags().size(); +} +inline int Information::camera_cap_flags_size() const { + return _internal_camera_cap_flags_size(); +} +inline void Information::clear_camera_cap_flags() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.camera_cap_flags_.Clear(); +} +inline ::mavsdk::rpc::camera_server::Information_CameraCapFlags Information::camera_cap_flags(int index) const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.camera_cap_flags) + return static_cast<::mavsdk::rpc::camera_server::Information_CameraCapFlags>(_internal_camera_cap_flags().Get(index)); +} +inline void Information::set_camera_cap_flags(int index, ::mavsdk::rpc::camera_server::Information_CameraCapFlags value) { + _internal_mutable_camera_cap_flags()->Set(index, value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.camera_cap_flags) +} +inline void Information::add_camera_cap_flags(::mavsdk::rpc::camera_server::Information_CameraCapFlags value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _internal_mutable_camera_cap_flags()->Add(value); + // @@protoc_insertion_point(field_add:mavsdk.rpc.camera_server.Information.camera_cap_flags) +} +inline const ::google::protobuf::RepeatedField& Information::camera_cap_flags() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.camera_server.Information.camera_cap_flags) + return _internal_camera_cap_flags(); +} +inline ::google::protobuf::RepeatedField* Information::mutable_camera_cap_flags() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.camera_server.Information.camera_cap_flags) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_camera_cap_flags(); +} +inline const ::google::protobuf::RepeatedField& Information::_internal_camera_cap_flags() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.camera_cap_flags_; +} +inline ::google::protobuf::RepeatedField* Information::_internal_mutable_camera_cap_flags() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.camera_cap_flags_; +} + // ------------------------------------------------------------------- // VideoStreamSettings @@ -14699,6 +14838,12 @@ inline void CaptureStatus::_internal_set_image_count(::int32_t value) { namespace google { namespace protobuf { +template <> +struct is_proto_enum<::mavsdk::rpc::camera_server::Information_CameraCapFlags> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::Information_CameraCapFlags>() { + return ::mavsdk::rpc::camera_server::Information_CameraCapFlags_descriptor(); +} template <> struct is_proto_enum<::mavsdk::rpc::camera_server::VideoStreamInfo_VideoStreamStatus> : std::true_type {}; template <> diff --git a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h index 61507398b0..5434801a3a 100644 --- a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h @@ -672,6 +672,83 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { return obj; } + static rpc::camera::Information::CameraCapFlags translateToRpcCameraCapFlags( + const mavsdk::Camera::Information::CameraCapFlags& camera_cap_flags) + { + switch (camera_cap_flags) { + default: + LogErr() << "Unknown camera_cap_flags enum value: " + << static_cast(camera_cap_flags); + // FALLTHROUGH + case mavsdk::Camera::Information::CameraCapFlags::CaptureVideo: + return rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_VIDEO; + case mavsdk::Camera::Information::CameraCapFlags::CaptureImage: + return rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_IMAGE; + case mavsdk::Camera::Information::CameraCapFlags::HasModes: + return rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_MODES; + case mavsdk::Camera::Information::CameraCapFlags::CanCaptureImageInVideoMode: + return rpc::camera:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; + case mavsdk::Camera::Information::CameraCapFlags::CanCaptureVideoInImageMode: + return rpc::camera:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; + case mavsdk::Camera::Information::CameraCapFlags::HasImageSurveyMode: + return rpc::camera:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE; + case mavsdk::Camera::Information::CameraCapFlags::HasBasicZoom: + return rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; + case mavsdk::Camera::Information::CameraCapFlags::HasBasicFocus: + return rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; + case mavsdk::Camera::Information::CameraCapFlags::HasVideoStream: + return rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; + case mavsdk::Camera::Information::CameraCapFlags::HasTrackingPoint: + return rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_POINT; + case mavsdk::Camera::Information::CameraCapFlags::HasTrackingRectangle: + return rpc::camera:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE; + case mavsdk::Camera::Information::CameraCapFlags::HasTrackingGeoStatus: + return rpc::camera:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS; + } + } + + static mavsdk::Camera::Information::CameraCapFlags + translateFromRpcCameraCapFlags(const rpc::camera::Information::CameraCapFlags camera_cap_flags) + { + switch (camera_cap_flags) { + default: + LogErr() << "Unknown camera_cap_flags enum value: " + << static_cast(camera_cap_flags); + // FALLTHROUGH + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_VIDEO: + return mavsdk::Camera::Information::CameraCapFlags::CaptureVideo; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_IMAGE: + return mavsdk::Camera::Information::CameraCapFlags::CaptureImage; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_MODES: + return mavsdk::Camera::Information::CameraCapFlags::HasModes; + case rpc::camera:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE: + return mavsdk::Camera::Information::CameraCapFlags::CanCaptureImageInVideoMode; + case rpc::camera:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE: + return mavsdk::Camera::Information::CameraCapFlags::CanCaptureVideoInImageMode; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE: + return mavsdk::Camera::Information::CameraCapFlags::HasImageSurveyMode; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM: + return mavsdk::Camera::Information::CameraCapFlags::HasBasicZoom; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS: + return mavsdk::Camera::Information::CameraCapFlags::HasBasicFocus; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM: + return mavsdk::Camera::Information::CameraCapFlags::HasVideoStream; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_POINT: + return mavsdk::Camera::Information::CameraCapFlags::HasTrackingPoint; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE: + return mavsdk::Camera::Information::CameraCapFlags::HasTrackingRectangle; + case rpc::camera::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS: + return mavsdk::Camera::Information::CameraCapFlags::HasTrackingGeoStatus; + } + } + static std::unique_ptr translateToRpcInformation(const mavsdk::Camera::Information& information) { @@ -681,6 +758,8 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { rpc_obj->set_model_name(information.model_name); + rpc_obj->set_firmware_version(information.firmware_version); + rpc_obj->set_focal_length_mm(information.focal_length_mm); rpc_obj->set_horizontal_sensor_size_mm(information.horizontal_sensor_size_mm); @@ -691,6 +770,16 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { rpc_obj->set_vertical_resolution_px(information.vertical_resolution_px); + rpc_obj->set_lens_id(information.lens_id); + + rpc_obj->set_definition_file_version(information.definition_file_version); + + rpc_obj->set_definition_file_uri(information.definition_file_uri); + + for (const auto& elem : information.camera_cap_flags) { + rpc_obj->add_camera_cap_flags(translateToRpcCameraCapFlags(elem)); + } + return rpc_obj; } @@ -703,6 +792,8 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { obj.model_name = information.model_name(); + obj.firmware_version = information.firmware_version(); + obj.focal_length_mm = information.focal_length_mm(); obj.horizontal_sensor_size_mm = information.horizontal_sensor_size_mm(); @@ -713,6 +804,17 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { obj.vertical_resolution_px = information.vertical_resolution_px(); + obj.lens_id = information.lens_id(); + + obj.definition_file_version = information.definition_file_version(); + + obj.definition_file_uri = information.definition_file_uri(); + + for (const auto& elem : information.camera_cap_flags()) { + obj.camera_cap_flags.push_back(translateFromRpcCameraCapFlags( + static_cast(elem))); + } + return obj; } diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index fd05e86dc1..1cc746cb60 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -112,6 +112,94 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer } } + static rpc::camera_server::Information::CameraCapFlags translateToRpcCameraCapFlags( + const mavsdk::CameraServer::Information::CameraCapFlags& camera_cap_flags) + { + switch (camera_cap_flags) { + default: + LogErr() << "Unknown camera_cap_flags enum value: " + << static_cast(camera_cap_flags); + // FALLTHROUGH + case mavsdk::CameraServer::Information::CameraCapFlags::CaptureVideo: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_VIDEO; + case mavsdk::CameraServer::Information::CameraCapFlags::CaptureImage: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_IMAGE; + case mavsdk::CameraServer::Information::CameraCapFlags::HasModes: + return rpc::camera_server::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_MODES; + case mavsdk::CameraServer::Information::CameraCapFlags::CanCaptureImageInVideoMode: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; + case mavsdk::CameraServer::Information::CameraCapFlags::CanCaptureVideoInImageMode: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; + case mavsdk::CameraServer::Information::CameraCapFlags::HasImageSurveyMode: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE; + case mavsdk::CameraServer::Information::CameraCapFlags::HasBasicZoom: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; + case mavsdk::CameraServer::Information::CameraCapFlags::HasBasicFocus: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; + case mavsdk::CameraServer::Information::CameraCapFlags::HasVideoStream: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; + case mavsdk::CameraServer::Information::CameraCapFlags::HasTrackingPoint: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_POINT; + case mavsdk::CameraServer::Information::CameraCapFlags::HasTrackingRectangle: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE; + case mavsdk::CameraServer::Information::CameraCapFlags::HasTrackingGeoStatus: + return rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS; + } + } + + static mavsdk::CameraServer::Information::CameraCapFlags translateFromRpcCameraCapFlags( + const rpc::camera_server::Information::CameraCapFlags camera_cap_flags) + { + switch (camera_cap_flags) { + default: + LogErr() << "Unknown camera_cap_flags enum value: " + << static_cast(camera_cap_flags); + // FALLTHROUGH + case rpc::camera_server::Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_VIDEO: + return mavsdk::CameraServer::Information::CameraCapFlags::CaptureVideo; + case rpc::camera_server::Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAPTURE_IMAGE: + return mavsdk::CameraServer::Information::CameraCapFlags::CaptureImage; + case rpc::camera_server::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_MODES: + return mavsdk::CameraServer::Information::CameraCapFlags::HasModes; + case rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE: + return mavsdk::CameraServer::Information::CameraCapFlags:: + CanCaptureImageInVideoMode; + case rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE: + return mavsdk::CameraServer::Information::CameraCapFlags:: + CanCaptureVideoInImageMode; + case rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE: + return mavsdk::CameraServer::Information::CameraCapFlags::HasImageSurveyMode; + case rpc::camera_server::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM: + return mavsdk::CameraServer::Information::CameraCapFlags::HasBasicZoom; + case rpc::camera_server::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS: + return mavsdk::CameraServer::Information::CameraCapFlags::HasBasicFocus; + case rpc::camera_server::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM: + return mavsdk::CameraServer::Information::CameraCapFlags::HasVideoStream; + case rpc::camera_server::Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_POINT: + return mavsdk::CameraServer::Information::CameraCapFlags::HasTrackingPoint; + case rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE: + return mavsdk::CameraServer::Information::CameraCapFlags::HasTrackingRectangle; + case rpc::camera_server:: + Information_CameraCapFlags_CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS: + return mavsdk::CameraServer::Information::CameraCapFlags::HasTrackingGeoStatus; + } + } + static std::unique_ptr translateToRpcInformation(const mavsdk::CameraServer::Information& information) { @@ -139,6 +227,10 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer rpc_obj->set_definition_file_uri(information.definition_file_uri); + for (const auto& elem : information.camera_cap_flags) { + rpc_obj->add_camera_cap_flags(translateToRpcCameraCapFlags(elem)); + } + return rpc_obj; } @@ -169,6 +261,11 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer obj.definition_file_uri = information.definition_file_uri(); + for (const auto& elem : information.camera_cap_flags()) { + obj.camera_cap_flags.push_back(translateFromRpcCameraCapFlags( + static_cast(elem))); + } + return obj; } From 148358f274b1e7c33fa649e62d3eb8b9e91ec571 Mon Sep 17 00:00:00 2001 From: tbago Date: Tue, 27 Feb 2024 16:36:40 +0800 Subject: [PATCH 3/3] system test: add camera information test --- src/system_tests/CMakeLists.txt | 1 + src/system_tests/camera_information.cpp | 90 +++++++++++++++++++++++++ 2 files changed, 91 insertions(+) create mode 100644 src/system_tests/camera_information.cpp diff --git a/src/system_tests/CMakeLists.txt b/src/system_tests/CMakeLists.txt index 068087c940..a4d87fdd9f 100644 --- a/src/system_tests/CMakeLists.txt +++ b/src/system_tests/CMakeLists.txt @@ -1,5 +1,6 @@ add_executable(system_tests_runner camera_take_photo.cpp + camera_information.cpp component_information.cpp action_arm_disarm.cpp param_set_and_get.cpp diff --git a/src/system_tests/camera_information.cpp b/src/system_tests/camera_information.cpp new file mode 100644 index 0000000000..9cf29aeaae --- /dev/null +++ b/src/system_tests/camera_information.cpp @@ -0,0 +1,90 @@ +#include "mavsdk.h" +#include "plugins/camera/camera.h" +#include "plugins/camera_server/camera_server.h" +#include "log.h" +#include +#include +#include +#include + +using namespace mavsdk; + +static constexpr auto vendor_name = "TEST_CAMERA_NAME"; +static constexpr auto model_name = "TEST_CAMERA_MODE_NAME"; +static constexpr auto firmware_version = "1.2.3.4"; +static constexpr auto focal_length_mm = 2.0; +static constexpr auto horizontal_sensor_size_mm = 3.14; +static constexpr auto vertical_sensor_size_mm = 2.55; +static constexpr auto horizontal_resolution_px = 1920; +static constexpr auto vertical_resolution_px = 1080; +static constexpr auto lens_id = 1; +static constexpr auto definition_file_version = 12; +static constexpr auto definition_file_uri = "ftp://192.168.0.1/test.xml"; +static std::vector camera_cap_flags = { + mavsdk::CameraServer::Information::CameraCapFlags::CaptureImage, + mavsdk::CameraServer::Information::CameraCapFlags::CaptureVideo, + mavsdk::CameraServer::Information::CameraCapFlags::HasModes, + mavsdk::CameraServer::Information::CameraCapFlags::HasVideoStream, +}; + +TEST(SystemTest, CameraInformation) +{ + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + + Mavsdk mavsdk_camera{Mavsdk::Configuration{Mavsdk::ComponentType::Camera}}; + + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + ASSERT_EQ(mavsdk_camera.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + auto camera_server = CameraServer{mavsdk_camera.server_component()}; + auto ret = camera_server.set_information({ + .vendor_name = vendor_name, + .model_name = model_name, + .firmware_version = firmware_version, + .focal_length_mm = focal_length_mm, + .horizontal_sensor_size_mm = horizontal_sensor_size_mm, + .vertical_sensor_size_mm = vertical_sensor_size_mm, + .horizontal_resolution_px = horizontal_resolution_px, + .vertical_resolution_px = vertical_resolution_px, + .lens_id = lens_id, + .definition_file_version = definition_file_version, + .definition_file_uri = definition_file_uri, + .camera_cap_flags = camera_cap_flags, + }); + ASSERT_EQ(ret, CameraServer::Result::Success); + + auto prom = std::promise>(); + auto fut = prom.get_future(); + std::once_flag flag; + + auto handle = mavsdk_groundstation.subscribe_on_new_system([&]() { + const auto system = mavsdk_groundstation.systems().back(); + if (system->is_connected() && system->has_camera()) { + std::call_once(flag, [&]() { prom.set_value(system); }); + } + }); + + ASSERT_EQ(fut.wait_for(std::chrono::seconds(10)), std::future_status::ready); + mavsdk_groundstation.unsubscribe_on_new_system(handle); + auto system = fut.get(); + + auto camera = Camera{system}; + + camera.subscribe_information([](mavsdk::Camera::Information info) { + LogDebug() << info; + ASSERT_EQ(info.vendor_name, vendor_name); + ASSERT_EQ(info.model_name, model_name); + ASSERT_EQ(info.firmware_version, firmware_version); + ASSERT_FLOAT_EQ(info.focal_length_mm, focal_length_mm); + ASSERT_FLOAT_EQ(info.horizontal_sensor_size_mm, horizontal_sensor_size_mm); + ASSERT_FLOAT_EQ(info.vertical_sensor_size_mm, vertical_sensor_size_mm); + ASSERT_EQ(info.horizontal_resolution_px, horizontal_resolution_px); + ASSERT_EQ(info.vertical_resolution_px, vertical_resolution_px); + ASSERT_EQ(info.lens_id, lens_id); + ASSERT_EQ(info.definition_file_version, definition_file_version); + ASSERT_EQ(info.definition_file_uri, definition_file_uri); + ASSERT_EQ(info.camera_cap_flags.size(), camera_cap_flags.size()); + }); + + std::this_thread::sleep_for(std::chrono::milliseconds(500)); +}