From e46e8c94f7541c7cb0b207b26481c4c4252cb64b Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 22 Mar 2024 12:32:53 +1300 Subject: [PATCH] camera_server: implement zoom This implements zoom for the camera server, range and continuous mode and adds an example to try it out. Signed-off-by: Julian Oes --- examples/CMakeLists.txt | 1 + examples/camera_zoom/CMakeLists.txt | 22 + examples/camera_zoom/camera_zoom.cpp | 129 + proto | 2 +- src/mavsdk/plugins/camera/camera_impl.cpp | 2 + .../plugins/camera_server/camera_server.cpp | 64 + .../camera_server/camera_server_impl.cpp | 259 +- .../camera_server/camera_server_impl.h | 106 +- .../plugins/camera_server/camera_server.h | 116 + .../camera_server/camera_server.grpc.pb.cc | 308 + .../camera_server/camera_server.grpc.pb.h | 1294 +- .../camera_server/camera_server.pb.cc | 3788 +++++- .../camera_server/camera_server.pb.h | 10654 ++++++++++------ .../camera_server_service_impl.h | 288 + 14 files changed, 12842 insertions(+), 4191 deletions(-) create mode 100644 examples/camera_zoom/CMakeLists.txt create mode 100644 examples/camera_zoom/camera_zoom.cpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 58888052ca..051ca757ab 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -13,6 +13,7 @@ add_subdirectory(calibrate) add_subdirectory(camera) add_subdirectory(camera_server) add_subdirectory(camera_settings) +add_subdirectory(camera_zoom) add_subdirectory(fly_mission) add_subdirectory(fly_multiple_drones) add_subdirectory(fly_qgc_mission) diff --git a/examples/camera_zoom/CMakeLists.txt b/examples/camera_zoom/CMakeLists.txt new file mode 100644 index 0000000000..815fdf7b49 --- /dev/null +++ b/examples/camera_zoom/CMakeLists.txt @@ -0,0 +1,22 @@ +cmake_minimum_required(VERSION 3.10.2) + +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +project(camera_zoom) + +add_executable(camera_zoom + camera_zoom.cpp +) + +find_package(MAVSDK REQUIRED) + +target_link_libraries(camera_zoom + MAVSDK::mavsdk +) + +if(NOT MSVC) + add_compile_options(camera_zoom PRIVATE -Wall -Wextra) +else() + add_compile_options(camera_zoom PRIVATE -WX -W2) +endif() diff --git a/examples/camera_zoom/camera_zoom.cpp b/examples/camera_zoom/camera_zoom.cpp new file mode 100644 index 0000000000..dd06f68c6b --- /dev/null +++ b/examples/camera_zoom/camera_zoom.cpp @@ -0,0 +1,129 @@ +// +// Example to demonstrate how to switch to photo mode and take a picture. +// + +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace mavsdk; +using std::chrono::seconds; +using std::this_thread::sleep_for; + +void usage(std::string bin_name) +{ + std::cerr << "Usage : " << bin_name << " \n" + << "Connection URL format should be :\n" + << " For TCP : tcp://[server_host][:server_port]\n" + << " For UDP : udp://[bind_host][:bind_port]\n" + << " For Serial : serial:///path/to/serial/dev[:baudrate]\n" + << "For example, to connect to the simulator use URL: udp://:14540\n"; +} + +int main(int argc, char** argv) +{ + if (argc != 2) { + usage(argv[0]); + return 1; + } + + Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); + + if (connection_result != ConnectionResult::Success) { + std::cerr << "Connection failed: " << connection_result << '\n'; + return 1; + } + + std::cout << "Waiting to discover system...\n"; + auto prom = std::promise>{}; + auto fut = prom.get_future(); + + // We wait for new systems to be discovered, once we find one that has a + // camera, we decide to use it. + Mavsdk::NewSystemHandle handle = mavsdk.subscribe_on_new_system([&mavsdk, &prom, &handle]() { + auto system = mavsdk.systems().back(); + + // TODO: filter for camera + // if (system->has_camera()) { + std::cout << "Discovered camera\n"; + + // Unsubscribe again as we only want to find one system. + mavsdk.unsubscribe_on_new_system(handle); + prom.set_value(system); + //} + }); + + // We usually receive heartbeats at 1Hz, therefore we should find a + // system after around 3 seconds max, surely. + if (fut.wait_for(seconds(5)) == std::future_status::timeout) { + std::cerr << "No camera found, exiting.\n"; + return 1; + } + + // Get discovered system now. + auto system = fut.get(); + + // Instantiate plugins. + auto camera = Camera{system}; + + // Zoom in + auto result = camera.zoom_range(2.0f); + if (result != Camera::Result::Success) { + std::cerr << "Zooming failed: " << result << '\n'; + return 1; + } + + // Wait a bit + sleep_for(seconds(4)); + + // Now try continuous zooming in. + result = camera.zoom_in_start(); + if (result != Camera::Result::Success) { + std::cerr << "Zooming in failed: " << result << '\n'; + return 1; + } + + sleep_for(seconds(1)); + + // Now try stopping. + result = camera.zoom_stop(); + if (result != Camera::Result::Success) { + std::cerr << "Stop zooming failed: " << result << '\n'; + return 1; + } + + sleep_for(seconds(1)); + + // And back out. + result = camera.zoom_out_start(); + if (result != Camera::Result::Success) { + std::cerr << "Zooming out failed: " << result << '\n'; + return 1; + } + + sleep_for(seconds(1)); + + // Stop again. + result = camera.zoom_stop(); + if (result != Camera::Result::Success) { + std::cerr << "Stop zooming failed: " << result << '\n'; + return 1; + } + + sleep_for(seconds(1)); + + // Zoom back out + result = camera.zoom_range(1.0f); + if (result != Camera::Result::Success) { + std::cerr << "Zooming failed: " << result << '\n'; + return 1; + } + + return 0; +} diff --git a/proto b/proto index 211476a2a2..c000fb508f 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 211476a2a28dcb2e3fa534d7e8c4fb434e4e6a86 +Subproject commit c000fb508ffa66b440ac746b2f594a6ee547afc2 diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index 712a750993..7fa5092b53 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -1071,6 +1071,8 @@ CameraImpl::camera_result_from_command_result(const MavlinkCommandSender::Result // FALLTHROUGH case MavlinkCommandSender::Result::Busy: return Camera::Result::Error; + case MavlinkCommandSender::Result::Failed: + return Camera::Result::Error; case MavlinkCommandSender::Result::Denied: // FALLTHROUGH case MavlinkCommandSender::Result::TemporarilyRejected: diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index ef75fa7cc0..b31b3af373 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -205,6 +205,70 @@ CameraServer::respond_reset_settings(CameraFeedback reset_settings_feedback) con return _impl->respond_reset_settings(reset_settings_feedback); } +CameraServer::ZoomInStartHandle +CameraServer::subscribe_zoom_in_start(const ZoomInStartCallback& callback) +{ + return _impl->subscribe_zoom_in_start(callback); +} + +void CameraServer::unsubscribe_zoom_in_start(ZoomInStartHandle handle) +{ + _impl->unsubscribe_zoom_in_start(handle); +} + +CameraServer::Result +CameraServer::respond_zoom_in_start(CameraFeedback zoom_in_start_feedback) const +{ + return _impl->respond_zoom_in_start(zoom_in_start_feedback); +} + +CameraServer::ZoomOutStartHandle +CameraServer::subscribe_zoom_out_start(const ZoomOutStartCallback& callback) +{ + return _impl->subscribe_zoom_out_start(callback); +} + +void CameraServer::unsubscribe_zoom_out_start(ZoomOutStartHandle handle) +{ + _impl->unsubscribe_zoom_out_start(handle); +} + +CameraServer::Result +CameraServer::respond_zoom_out_start(CameraFeedback zoom_out_start_feedback) const +{ + return _impl->respond_zoom_out_start(zoom_out_start_feedback); +} + +CameraServer::ZoomStopHandle CameraServer::subscribe_zoom_stop(const ZoomStopCallback& callback) +{ + return _impl->subscribe_zoom_stop(callback); +} + +void CameraServer::unsubscribe_zoom_stop(ZoomStopHandle handle) +{ + _impl->unsubscribe_zoom_stop(handle); +} + +CameraServer::Result CameraServer::respond_zoom_stop(CameraFeedback zoom_stop_feedback) const +{ + return _impl->respond_zoom_stop(zoom_stop_feedback); +} + +CameraServer::ZoomRangeHandle CameraServer::subscribe_zoom_range(const ZoomRangeCallback& callback) +{ + return _impl->subscribe_zoom_range(callback); +} + +void CameraServer::unsubscribe_zoom_range(ZoomRangeHandle handle) +{ + _impl->unsubscribe_zoom_range(handle); +} + +CameraServer::Result CameraServer::respond_zoom_range(CameraFeedback zoom_range_feedback) const +{ + return _impl->respond_zoom_range(zoom_range_feedback); +} + bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 293d661c68..d6dc62df4f 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -326,7 +326,7 @@ CameraServerImpl::respond_start_video(CameraServer::CameraFeedback start_video_f auto command_ack = _server_component_impl->make_command_ack_message( _last_start_video_command, MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - break; + return CameraServer::Result::Success; } case CameraServer::CameraFeedback::Busy: { auto command_ack = _server_component_impl->make_command_ack_message( @@ -341,7 +341,6 @@ CameraServerImpl::respond_start_video(CameraServer::CameraFeedback start_video_f return CameraServer::Result::Success; } } - return CameraServer::Result::Success; } CameraServer::StopVideoHandle @@ -367,7 +366,7 @@ CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_fee auto command_ack = _server_component_impl->make_command_ack_message( _last_stop_video_command, MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - break; + return CameraServer::Result::Success; } case CameraServer::CameraFeedback::Busy: { auto command_ack = _server_component_impl->make_command_ack_message( @@ -382,7 +381,6 @@ CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_fee return CameraServer::Result::Success; } } - return CameraServer::Result::Success; } CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming( @@ -409,7 +407,7 @@ CameraServer::Result CameraServerImpl::respond_start_video_streaming( auto command_ack = _server_component_impl->make_command_ack_message( _last_start_video_streaming_command, MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - break; + return CameraServer::Result::Success; } case CameraServer::CameraFeedback::Busy: { auto command_ack = _server_component_impl->make_command_ack_message( @@ -424,7 +422,6 @@ CameraServer::Result CameraServerImpl::respond_start_video_streaming( return CameraServer::Result::Success; } } - return CameraServer::Result::Success; } CameraServer::StopVideoStreamingHandle CameraServerImpl::subscribe_stop_video_streaming( @@ -451,7 +448,7 @@ CameraServer::Result CameraServerImpl::respond_stop_video_streaming( auto command_ack = _server_component_impl->make_command_ack_message( _last_stop_video_streaming_command, MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - break; + return CameraServer::Result::Success; } case CameraServer::CameraFeedback::Busy: { auto command_ack = _server_component_impl->make_command_ack_message( @@ -466,7 +463,6 @@ CameraServer::Result CameraServerImpl::respond_stop_video_streaming( return CameraServer::Result::Success; } } - return CameraServer::Result::Success; } CameraServer::SetModeHandle @@ -492,7 +488,7 @@ CameraServerImpl::respond_set_mode(CameraServer::CameraFeedback set_mode_feedbac auto command_ack = _server_component_impl->make_command_ack_message( _last_set_mode_command, MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - break; + return CameraServer::Result::Success; } case CameraServer::CameraFeedback::Busy: { auto command_ack = _server_component_impl->make_command_ack_message( @@ -507,7 +503,6 @@ CameraServerImpl::respond_set_mode(CameraServer::CameraFeedback set_mode_feedbac return CameraServer::Result::Success; } } - return CameraServer::Result::Success; } CameraServer::StorageInformationHandle CameraServerImpl::subscribe_storage_information( @@ -697,7 +692,7 @@ CameraServerImpl::respond_format_storage(CameraServer::CameraFeedback format_sto auto command_ack = _server_component_impl->make_command_ack_message( _last_format_storage_command, MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - break; + return CameraServer::Result::Success; } case CameraServer::CameraFeedback::Busy: { auto command_ack = _server_component_impl->make_command_ack_message( @@ -712,7 +707,6 @@ CameraServerImpl::respond_format_storage(CameraServer::CameraFeedback format_sto return CameraServer::Result::Success; } } - return CameraServer::Result::Success; } CameraServer::ResetSettingsHandle @@ -738,7 +732,7 @@ CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_sett auto command_ack = _server_component_impl->make_command_ack_message( _last_reset_settings_command, MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - break; + return CameraServer::Result::Success; } case CameraServer::CameraFeedback::Busy: { auto command_ack = _server_component_impl->make_command_ack_message( @@ -753,7 +747,6 @@ CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_sett return CameraServer::Result::Success; } } - return CameraServer::Result::Success; } void CameraServerImpl::start_image_capture_interval(float interval_s, int32_t count, int32_t index) @@ -1143,13 +1136,81 @@ CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandL auto zoom_type = static_cast(command.params.param1); auto zoom_value = command.params.param2; - UNUSED(zoom_type); - UNUSED(zoom_value); + if (_zoom_in_start_callbacks.empty() && _zoom_out_start_callbacks.empty() && + _zoom_stop_callbacks.empty() && _zoom_range_callbacks.empty()) { + LogWarn() << "No camera zoom is supported"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } - LogDebug() << "unsupported set camera zoom request"; + auto unsupported = [&]() { + LogWarn() << "unsupported set camera zoom type (" << (int)zoom_type << ") request"; + }; - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + switch (zoom_type) { + case ZOOM_TYPE_CONTINUOUS: + if (zoom_value == -1.f) { + if (_zoom_out_start_callbacks.empty()) { + unsupported(); + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_DENIED); + } else { + _last_zoom_out_start_command = command; + int dummy = 0; + _zoom_out_start_callbacks(dummy); + } + } else if (zoom_value == 1.f) { + if (_zoom_in_start_callbacks.empty()) { + unsupported(); + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_DENIED); + } else { + _last_zoom_in_start_command = command; + int dummy = 0; + _zoom_in_start_callbacks(dummy); + } + } else if (zoom_value == 0.f) { + if (_zoom_stop_callbacks.empty()) { + unsupported(); + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_DENIED); + } else { + _last_zoom_stop_command = command; + int dummy = 0; + _zoom_stop_callbacks(dummy); + } + } else { + LogWarn() << "Invalid zoom value"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_DENIED); + } + break; + case ZOOM_TYPE_RANGE: + if (_zoom_range_callbacks.empty()) { + unsupported(); + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_DENIED); + + } else { + _last_zoom_range_command = command; + _zoom_range_callbacks(zoom_value); + } + break; + case ZOOM_TYPE_STEP: + // Fallthrough + case ZOOM_TYPE_FOCAL_LENGTH: + // Fallthrough + case ZOOM_TYPE_HORIZONTAL_FOV: + // Fallthrough + default: + unsupported(); + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_DENIED); + break; + } + + // For any success so far, we don't ack yet, but later when the respond function is called. + return std::nullopt; } std::optional @@ -1402,4 +1463,164 @@ std::optional CameraServerImpl::process_video_stream_stat return std::nullopt; } +CameraServer::ZoomInStartHandle +CameraServerImpl::subscribe_zoom_in_start(const CameraServer::ZoomInStartCallback& callback) +{ + return _zoom_in_start_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle) +{ + _zoom_in_start_callbacks.unsubscribe(handle); +} + +CameraServer::Result +CameraServerImpl::respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback) +{ + switch (zoom_in_start_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_in_start_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_in_start_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_in_start_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } +} + +CameraServer::ZoomOutStartHandle +CameraServerImpl::subscribe_zoom_out_start(const CameraServer::ZoomOutStartCallback& callback) +{ + return _zoom_out_start_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle) +{ + _zoom_out_start_callbacks.unsubscribe(handle); +} + +CameraServer::Result +CameraServerImpl::respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback) +{ + switch (zoom_out_start_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_out_start_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_out_start_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_out_start_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } +} + +CameraServer::ZoomStopHandle +CameraServerImpl::subscribe_zoom_stop(const CameraServer::ZoomStopCallback& callback) +{ + return _zoom_stop_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle) +{ + _zoom_stop_callbacks.unsubscribe(handle); +} + +CameraServer::Result +CameraServerImpl::respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback) +{ + switch (zoom_stop_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_stop_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_stop_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_stop_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } +} + +CameraServer::ZoomRangeHandle +CameraServerImpl::subscribe_zoom_range(const CameraServer::ZoomRangeCallback& callback) +{ + return _zoom_range_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle) +{ + _zoom_range_callbacks.unsubscribe(handle); +} + +CameraServer::Result +CameraServerImpl::respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback) +{ + switch (zoom_range_feedback) { + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_range_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_range_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_zoom_range_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Unknown: + // Fallthrough + default: + return CameraServer::Result::Error; + } +} + } // namespace mavsdk diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 90dc8698a0..a61d6c72a6 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -76,6 +76,24 @@ class CameraServerImpl : public ServerPluginImplBase { CameraServer::Result respond_reset_settings(CameraServer::CameraFeedback reset_settings_feedback); + CameraServer::ZoomInStartHandle + subscribe_zoom_in_start(const CameraServer::ZoomInStartCallback& callback); + void unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle); + CameraServer::Result respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback); + CameraServer::ZoomOutStartHandle + subscribe_zoom_out_start(const CameraServer::ZoomOutStartCallback& callback); + void unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle); + CameraServer::Result + respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback); + CameraServer::ZoomStopHandle + subscribe_zoom_stop(const CameraServer::ZoomStopCallback& callback); + void unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle); + CameraServer::Result respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback); + CameraServer::ZoomRangeHandle + subscribe_zoom_range(const CameraServer::ZoomRangeCallback& callback); + void unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle); + CameraServer::Result respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback); + private: enum StatusFlags { IN_PROGRESS = 1 << 0, @@ -88,45 +106,6 @@ class CameraServerImpl : public ServerPluginImplBase { ENABLE = 1, }; - bool _is_information_set{}; - CameraServer::Information _information{}; - bool _is_video_streaming_set{}; - CameraServer::VideoStreaming _video_streaming{}; - - CameraServer::CaptureStatus _capture_status{}; - - // CAMERA_CAPTURE_STATUS fields - // TODO: how do we keep this info in sync between plugin instances? - bool _is_image_capture_in_progress{}; - bool _is_image_capture_interval_set{}; - float _image_capture_timer_interval_s{}; - void* _image_capture_timer_cookie{}; - int32_t _image_capture_count{}; - - CallbackList _take_photo_callbacks{}; - CallbackList _start_video_callbacks{}; - CallbackList _stop_video_callbacks{}; - CallbackList _start_video_streaming_callbacks{}; - CallbackList _stop_video_streaming_callbacks{}; - CallbackList _set_mode_callbacks{}; - CallbackList _storage_information_callbacks{}; - CallbackList _capture_status_callbacks{}; - CallbackList _format_storage_callbacks{}; - CallbackList _reset_settings_callbacks{}; - - MavlinkCommandReceiver::CommandLong _last_take_photo_command; - MavlinkCommandReceiver::CommandLong _last_start_video_command; - MavlinkCommandReceiver::CommandLong _last_stop_video_command; - MavlinkCommandReceiver::CommandLong _last_start_video_streaming_command; - MavlinkCommandReceiver::CommandLong _last_stop_video_streaming_command; - MavlinkCommandReceiver::CommandLong _last_set_mode_command; - MavlinkCommandReceiver::CommandLong _last_storage_information_command; - MavlinkCommandReceiver::CommandLong _last_capture_status_command; - MavlinkCommandReceiver::CommandLong _last_format_storage_command; - MavlinkCommandReceiver::CommandLong _last_reset_settings_command; - - uint8_t _last_storage_id; - bool parse_version_string(const std::string& version_str); bool parse_version_string(const std::string& version_str, uint32_t& version); void start_image_capture_interval(float interval, int32_t count, int32_t index); @@ -172,6 +151,55 @@ class CameraServerImpl : public ServerPluginImplBase { process_video_stream_status_request(const MavlinkCommandReceiver::CommandLong& command); void send_capture_status(); + + bool _is_information_set{}; + CameraServer::Information _information{}; + bool _is_video_streaming_set{}; + CameraServer::VideoStreaming _video_streaming{}; + + CameraServer::CaptureStatus _capture_status{}; + + // CAMERA_CAPTURE_STATUS fields + // TODO: how do we keep this info in sync between plugin instances? + bool _is_image_capture_in_progress{}; + bool _is_image_capture_interval_set{}; + float _image_capture_timer_interval_s{}; + void* _image_capture_timer_cookie{}; + int32_t _image_capture_count{}; + + CallbackList _take_photo_callbacks{}; + CallbackList _start_video_callbacks{}; + CallbackList _stop_video_callbacks{}; + CallbackList _start_video_streaming_callbacks{}; + CallbackList _stop_video_streaming_callbacks{}; + CallbackList _set_mode_callbacks{}; + CallbackList _storage_information_callbacks{}; + CallbackList _capture_status_callbacks{}; + CallbackList _format_storage_callbacks{}; + CallbackList _reset_settings_callbacks{}; + + CallbackList _zoom_in_start_callbacks{}; + CallbackList _zoom_out_start_callbacks{}; + CallbackList _zoom_stop_callbacks{}; + CallbackList _zoom_range_callbacks{}; + + MavlinkCommandReceiver::CommandLong _last_take_photo_command; + MavlinkCommandReceiver::CommandLong _last_start_video_command; + MavlinkCommandReceiver::CommandLong _last_stop_video_command; + MavlinkCommandReceiver::CommandLong _last_start_video_streaming_command; + MavlinkCommandReceiver::CommandLong _last_stop_video_streaming_command; + MavlinkCommandReceiver::CommandLong _last_set_mode_command; + MavlinkCommandReceiver::CommandLong _last_storage_information_command; + MavlinkCommandReceiver::CommandLong _last_capture_status_command; + MavlinkCommandReceiver::CommandLong _last_format_storage_command; + MavlinkCommandReceiver::CommandLong _last_reset_settings_command; + + MavlinkCommandReceiver::CommandLong _last_zoom_in_start_command; + MavlinkCommandReceiver::CommandLong _last_zoom_out_start_command; + MavlinkCommandReceiver::CommandLong _last_zoom_stop_command; + MavlinkCommandReceiver::CommandLong _last_zoom_range_command; + + uint8_t _last_storage_id; }; } // namespace mavsdk 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..980496d90e 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 @@ -719,6 +719,122 @@ class CameraServer : public ServerPluginBase { */ Result respond_reset_settings(CameraFeedback reset_settings_feedback) const; + /** + * @brief Callback type for subscribe_zoom_in_start. + */ + using ZoomInStartCallback = std::function; + + /** + * @brief Handle type for subscribe_zoom_in_start. + */ + using ZoomInStartHandle = Handle; + + /** + * @brief Subscribe to zoom in start command + */ + ZoomInStartHandle subscribe_zoom_in_start(const ZoomInStartCallback& callback); + + /** + * @brief Unsubscribe from subscribe_zoom_in_start + */ + void unsubscribe_zoom_in_start(ZoomInStartHandle handle); + + /** + * @brief Respond to zoom in start. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_zoom_in_start(CameraFeedback zoom_in_start_feedback) const; + + /** + * @brief Callback type for subscribe_zoom_out_start. + */ + using ZoomOutStartCallback = std::function; + + /** + * @brief Handle type for subscribe_zoom_out_start. + */ + using ZoomOutStartHandle = Handle; + + /** + * @brief Subscribe to zoom out start command + */ + ZoomOutStartHandle subscribe_zoom_out_start(const ZoomOutStartCallback& callback); + + /** + * @brief Unsubscribe from subscribe_zoom_out_start + */ + void unsubscribe_zoom_out_start(ZoomOutStartHandle handle); + + /** + * @brief Respond to zoom out start. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_zoom_out_start(CameraFeedback zoom_out_start_feedback) const; + + /** + * @brief Callback type for subscribe_zoom_stop. + */ + using ZoomStopCallback = std::function; + + /** + * @brief Handle type for subscribe_zoom_stop. + */ + using ZoomStopHandle = Handle; + + /** + * @brief Subscribe to zoom stop command + */ + ZoomStopHandle subscribe_zoom_stop(const ZoomStopCallback& callback); + + /** + * @brief Unsubscribe from subscribe_zoom_stop + */ + void unsubscribe_zoom_stop(ZoomStopHandle handle); + + /** + * @brief Respond to zoom stop. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_zoom_stop(CameraFeedback zoom_stop_feedback) const; + + /** + * @brief Callback type for subscribe_zoom_range. + */ + using ZoomRangeCallback = std::function; + + /** + * @brief Handle type for subscribe_zoom_range. + */ + using ZoomRangeHandle = Handle; + + /** + * @brief Subscribe to zoom range command + */ + ZoomRangeHandle subscribe_zoom_range(const ZoomRangeCallback& callback); + + /** + * @brief Unsubscribe from subscribe_zoom_range + */ + void unsubscribe_zoom_range(ZoomRangeHandle handle); + + /** + * @brief Respond to zoom range. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_zoom_range(CameraFeedback zoom_range_feedback) const; + /** * @brief Copy constructor. */ 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..627c0ba727 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 @@ -47,6 +47,14 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/RespondFormatStorage", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeResetSettings", "/mavsdk.rpc.camera_server.CameraServerService/RespondResetSettings", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomInStart", + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomInStart", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomOutStart", + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomOutStart", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomStop", + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomStop", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomRange", + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomRange", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -79,6 +87,14 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> , rpcmethod_RespondFormatStorage_(CameraServerService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeResetSettings_(CameraServerService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_RespondResetSettings_(CameraServerService_method_names[22], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeZoomInStart_(CameraServerService_method_names[23], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondZoomInStart_(CameraServerService_method_names[24], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeZoomOutStart_(CameraServerService_method_names[25], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondZoomOutStart_(CameraServerService_method_names[26], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeZoomStop_(CameraServerService_method_names[27], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondZoomStop_(CameraServerService_method_names[28], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeZoomRange_(CameraServerService_method_names[29], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondZoomRange_(CameraServerService_method_names[30], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -540,6 +556,162 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSet return result; } +::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* CameraServerService::Stub::SubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::ZoomInStartResponse>::Create(channel_.get(), rpcmethod_SubscribeZoomInStart_, context, request); +} + +void CameraServerService::Stub::async::SubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::ZoomInStartResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeZoomInStart_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* CameraServerService::Stub::AsyncSubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ZoomInStartResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeZoomInStart_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* CameraServerService::Stub::PrepareAsyncSubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ZoomInStartResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeZoomInStart_, context, request, false, nullptr); +} + +::grpc::Status CameraServerService::Stub::RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondZoomInStart_, context, request, response); +} + +void CameraServerService::Stub::async::RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondZoomInStart_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondZoomInStart_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* CameraServerService::Stub::PrepareAsyncRespondZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse, ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondZoomInStart_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* CameraServerService::Stub::AsyncRespondZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondZoomInStartRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* CameraServerService::Stub::SubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>::Create(channel_.get(), rpcmethod_SubscribeZoomOutStart_, context, request); +} + +void CameraServerService::Stub::async::SubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeZoomOutStart_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* CameraServerService::Stub::AsyncSubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeZoomOutStart_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* CameraServerService::Stub::PrepareAsyncSubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeZoomOutStart_, context, request, false, nullptr); +} + +::grpc::Status CameraServerService::Stub::RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondZoomOutStart_, context, request, response); +} + +void CameraServerService::Stub::async::RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondZoomOutStart_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondZoomOutStart_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* CameraServerService::Stub::PrepareAsyncRespondZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse, ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondZoomOutStart_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* CameraServerService::Stub::AsyncRespondZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondZoomOutStartRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>* CameraServerService::Stub::SubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::ZoomStopResponse>::Create(channel_.get(), rpcmethod_SubscribeZoomStop_, context, request); +} + +void CameraServerService::Stub::async::SubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomStopResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::ZoomStopResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeZoomStop_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>* CameraServerService::Stub::AsyncSubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ZoomStopResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeZoomStop_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>* CameraServerService::Stub::PrepareAsyncSubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ZoomStopResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeZoomStop_, context, request, false, nullptr); +} + +::grpc::Status CameraServerService::Stub::RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::mavsdk::rpc::camera_server::RespondZoomStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondZoomStop_, context, request, response); +} + +void CameraServerService::Stub::async::RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::mavsdk::rpc::camera_server::RespondZoomStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondZoomStop_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondZoomStop_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* CameraServerService::Stub::PrepareAsyncRespondZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondZoomStopResponse, ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondZoomStop_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* CameraServerService::Stub::AsyncRespondZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondZoomStopRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* CameraServerService::Stub::SubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::ZoomRangeResponse>::Create(channel_.get(), rpcmethod_SubscribeZoomRange_, context, request); +} + +void CameraServerService::Stub::async::SubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::ZoomRangeResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeZoomRange_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* CameraServerService::Stub::AsyncSubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ZoomRangeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeZoomRange_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* CameraServerService::Stub::PrepareAsyncSubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ZoomRangeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeZoomRange_, context, request, false, nullptr); +} + +::grpc::Status CameraServerService::Stub::RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondZoomRange_, context, request, response); +} + +void CameraServerService::Stub::async::RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondZoomRange_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondZoomRange_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* CameraServerService::Stub::PrepareAsyncRespondZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse, ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondZoomRange_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* CameraServerService::Stub::AsyncRespondZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondZoomRangeRaw(context, request, cq); + result->StartCall(); + return result; +} + CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[0], @@ -771,6 +943,86 @@ CameraServerService::Service::Service() { ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* resp) { return service->RespondResetSettings(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[23], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest, ::mavsdk::rpc::camera_server::ZoomInStartResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::ZoomInStartResponse>* writer) { + return service->SubscribeZoomInStart(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[24], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* req, + ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* resp) { + return service->RespondZoomInStart(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[25], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest, ::mavsdk::rpc::camera_server::ZoomOutStartResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::ZoomOutStartResponse>* writer) { + return service->SubscribeZoomOutStart(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[26], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* req, + ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* resp) { + return service->RespondZoomOutStart(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[27], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest, ::mavsdk::rpc::camera_server::ZoomStopResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::ZoomStopResponse>* writer) { + return service->SubscribeZoomStop(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[28], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::mavsdk::rpc::camera_server::RespondZoomStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* req, + ::mavsdk::rpc::camera_server::RespondZoomStopResponse* resp) { + return service->RespondZoomStop(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[29], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest, ::mavsdk::rpc::camera_server::ZoomRangeResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::ZoomRangeResponse>* writer) { + return service->SubscribeZoomRange(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[30], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* req, + ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* resp) { + return service->RespondZoomRange(ctx, req, resp); + }, this))); } CameraServerService::Service::~Service() { @@ -937,6 +1189,62 @@ ::grpc::Status CameraServerService::Service::RespondResetSettings(::grpc::Server return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::SubscribeZoomInStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::RespondZoomInStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SubscribeZoomOutStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::RespondZoomOutStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SubscribeZoomStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::RespondZoomStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SubscribeZoomRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::RespondZoomRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc 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..f1c640c783 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 @@ -242,6 +242,78 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>> PrepareAsyncRespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>>(PrepareAsyncRespondResetSettingsRaw(context, request, cq)); } + // Subscribe to zoom in start command + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>> SubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>>(SubscribeZoomInStartRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>> AsyncSubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>>(AsyncSubscribeZoomInStartRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>> PrepareAsyncSubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>>(PrepareAsyncSubscribeZoomInStartRaw(context, request, cq)); + } + // Respond to zoom in start. + virtual ::grpc::Status RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>> AsyncRespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>>(AsyncRespondZoomInStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>> PrepareAsyncRespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>>(PrepareAsyncRespondZoomInStartRaw(context, request, cq)); + } + // Subscribe to zoom out start command + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>> SubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>>(SubscribeZoomOutStartRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>> AsyncSubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>>(AsyncSubscribeZoomOutStartRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>> PrepareAsyncSubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>>(PrepareAsyncSubscribeZoomOutStartRaw(context, request, cq)); + } + // Respond to zoom out start. + virtual ::grpc::Status RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>> AsyncRespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>>(AsyncRespondZoomOutStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>> PrepareAsyncRespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>>(PrepareAsyncRespondZoomOutStartRaw(context, request, cq)); + } + // Subscribe to zoom stop command + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>> SubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>>(SubscribeZoomStopRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>> AsyncSubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>>(AsyncSubscribeZoomStopRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>> PrepareAsyncSubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>>(PrepareAsyncSubscribeZoomStopRaw(context, request, cq)); + } + // Respond to zoom stop. + virtual ::grpc::Status RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>> AsyncRespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>>(AsyncRespondZoomStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>> PrepareAsyncRespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>>(PrepareAsyncRespondZoomStopRaw(context, request, cq)); + } + // Subscribe to zoom range command + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>> SubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>>(SubscribeZoomRangeRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>> AsyncSubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>>(AsyncSubscribeZoomRangeRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>> PrepareAsyncSubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>>(PrepareAsyncSubscribeZoomRangeRaw(context, request, cq)); + } + // Respond to zoom range. + virtual ::grpc::Status RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>> AsyncRespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>>(AsyncRespondZoomRangeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>> PrepareAsyncRespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>>(PrepareAsyncRespondZoomRangeRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -304,6 +376,26 @@ class CameraServerService final { // Respond to reset settings from SubscribeResetSettings. virtual void RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, std::function) = 0; virtual void RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to zoom in start command + virtual void SubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* reactor) = 0; + // Respond to zoom in start. + virtual void RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response, std::function) = 0; + virtual void RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to zoom out start command + virtual void SubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* reactor) = 0; + // Respond to zoom out start. + virtual void RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response, std::function) = 0; + virtual void RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to zoom stop command + virtual void SubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomStopResponse>* reactor) = 0; + // Respond to zoom stop. + virtual void RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response, std::function) = 0; + virtual void RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to zoom range command + virtual void SubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* reactor) = 0; + // Respond to zoom range. + virtual void RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response, std::function) = 0; + virtual void RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -365,6 +457,26 @@ class CameraServerService final { virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* PrepareAsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* AsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* PrepareAsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* SubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* AsyncSubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* PrepareAsyncSubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* AsyncRespondZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* PrepareAsyncRespondZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* SubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* AsyncSubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* PrepareAsyncSubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* AsyncRespondZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* PrepareAsyncRespondZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>* SubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>* AsyncSubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomStopResponse>* PrepareAsyncSubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* AsyncRespondZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* PrepareAsyncRespondZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* SubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* AsyncSubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* PrepareAsyncSubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* AsyncRespondZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* PrepareAsyncRespondZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -550,6 +662,70 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>> PrepareAsyncRespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>>(PrepareAsyncRespondResetSettingsRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>> SubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>>(SubscribeZoomInStartRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>> AsyncSubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>>(AsyncSubscribeZoomInStartRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>> PrepareAsyncSubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>>(PrepareAsyncSubscribeZoomInStartRaw(context, request, cq)); + } + ::grpc::Status RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>> AsyncRespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>>(AsyncRespondZoomInStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>> PrepareAsyncRespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>>(PrepareAsyncRespondZoomInStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>> SubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>>(SubscribeZoomOutStartRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>> AsyncSubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>>(AsyncSubscribeZoomOutStartRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>> PrepareAsyncSubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>>(PrepareAsyncSubscribeZoomOutStartRaw(context, request, cq)); + } + ::grpc::Status RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>> AsyncRespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>>(AsyncRespondZoomOutStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>> PrepareAsyncRespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>>(PrepareAsyncRespondZoomOutStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>> SubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>>(SubscribeZoomStopRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>> AsyncSubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>>(AsyncSubscribeZoomStopRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>> PrepareAsyncSubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>>(PrepareAsyncSubscribeZoomStopRaw(context, request, cq)); + } + ::grpc::Status RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>> AsyncRespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>>(AsyncRespondZoomStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>> PrepareAsyncRespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>>(PrepareAsyncRespondZoomStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>> SubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>>(SubscribeZoomRangeRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>> AsyncSubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>>(AsyncSubscribeZoomRangeRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>> PrepareAsyncSubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>>(PrepareAsyncSubscribeZoomRangeRaw(context, request, cq)); + } + ::grpc::Status RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>> AsyncRespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>>(AsyncRespondZoomRangeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>> PrepareAsyncRespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>>(PrepareAsyncRespondZoomRangeRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -589,6 +765,18 @@ class CameraServerService final { void SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* reactor) override; void RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, std::function) override; void RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* reactor) override; + void RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response, std::function) override; + void RespondZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* reactor) override; + void RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response, std::function) override; + void RespondZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomStopResponse>* reactor) override; + void RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response, std::function) override; + void RespondZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* reactor) override; + void RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response, std::function) override; + void RespondZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -656,6 +844,26 @@ class CameraServerService final { ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* PrepareAsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; ::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; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* SubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* AsyncSubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* PrepareAsyncSubscribeZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* AsyncRespondZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* PrepareAsyncRespondZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* SubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* AsyncSubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* PrepareAsyncSubscribeZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* AsyncRespondZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* PrepareAsyncRespondZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>* SubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>* AsyncSubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomStopResponse>* PrepareAsyncSubscribeZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* AsyncRespondZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* PrepareAsyncRespondZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* SubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* AsyncSubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* PrepareAsyncSubscribeZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* AsyncRespondZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* PrepareAsyncRespondZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetVideoStreaming_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; @@ -679,6 +887,14 @@ class CameraServerService final { const ::grpc::internal::RpcMethod rpcmethod_RespondFormatStorage_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeResetSettings_; const ::grpc::internal::RpcMethod rpcmethod_RespondResetSettings_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeZoomInStart_; + const ::grpc::internal::RpcMethod rpcmethod_RespondZoomInStart_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeZoomOutStart_; + const ::grpc::internal::RpcMethod rpcmethod_RespondZoomOutStart_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeZoomStop_; + const ::grpc::internal::RpcMethod rpcmethod_RespondZoomStop_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeZoomRange_; + const ::grpc::internal::RpcMethod rpcmethod_RespondZoomRange_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -732,6 +948,22 @@ class CameraServerService final { virtual ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer); // Respond to reset settings from SubscribeResetSettings. virtual ::grpc::Status RespondResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response); + // Subscribe to zoom in start command + virtual ::grpc::Status SubscribeZoomInStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* writer); + // Respond to zoom in start. + virtual ::grpc::Status RespondZoomInStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response); + // Subscribe to zoom out start command + virtual ::grpc::Status SubscribeZoomOutStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* writer); + // Respond to zoom out start. + virtual ::grpc::Status RespondZoomOutStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response); + // Subscribe to zoom stop command + virtual ::grpc::Status SubscribeZoomStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* writer); + // Respond to zoom stop. + virtual ::grpc::Status RespondZoomStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response); + // Subscribe to zoom range command + virtual ::grpc::Status SubscribeZoomRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* writer); + // Respond to zoom range. + virtual ::grpc::Status RespondZoomRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -1193,7 +1425,167 @@ class CameraServerService final { ::grpc::Service::RequestAsyncUnary(22, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > AsyncService; + template + class WithAsyncMethod_SubscribeZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeZoomInStart() { + ::grpc::Service::MarkMethodAsync(23); + } + ~WithAsyncMethod_SubscribeZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeZoomInStart(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(23, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondZoomInStart() { + ::grpc::Service::MarkMethodAsync(24); + } + ~WithAsyncMethod_RespondZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondZoomInStart(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(24, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeZoomOutStart() { + ::grpc::Service::MarkMethodAsync(25); + } + ~WithAsyncMethod_SubscribeZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeZoomOutStart(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(25, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondZoomOutStart() { + ::grpc::Service::MarkMethodAsync(26); + } + ~WithAsyncMethod_RespondZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondZoomOutStart(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(26, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeZoomStop() { + ::grpc::Service::MarkMethodAsync(27); + } + ~WithAsyncMethod_SubscribeZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeZoomStop(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(27, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondZoomStop() { + ::grpc::Service::MarkMethodAsync(28); + } + ~WithAsyncMethod_RespondZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondZoomStop(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(28, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeZoomRange() { + ::grpc::Service::MarkMethodAsync(29); + } + ~WithAsyncMethod_SubscribeZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeZoomRange(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(29, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondZoomRange() { + ::grpc::Service::MarkMethodAsync(30); + } + ~WithAsyncMethod_RespondZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondZoomRange(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(30, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -1765,7 +2157,203 @@ 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; + template + class WithCallbackMethod_SubscribeZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeZoomInStart() { + ::grpc::Service::MarkMethodCallback(23, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest, ::mavsdk::rpc::camera_server::ZoomInStartResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* request) { return this->SubscribeZoomInStart(context, request); })); + } + ~WithCallbackMethod_SubscribeZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* SubscribeZoomInStart( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_RespondZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondZoomInStart() { + ::grpc::Service::MarkMethodCallback(24, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* response) { return this->RespondZoomInStart(context, request, response); }));} + void SetMessageAllocatorFor_RespondZoomInStart( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(24); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondZoomInStart( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeZoomOutStart() { + ::grpc::Service::MarkMethodCallback(25, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest, ::mavsdk::rpc::camera_server::ZoomOutStartResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* request) { return this->SubscribeZoomOutStart(context, request); })); + } + ~WithCallbackMethod_SubscribeZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* SubscribeZoomOutStart( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_RespondZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondZoomOutStart() { + ::grpc::Service::MarkMethodCallback(26, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* request, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* response) { return this->RespondZoomOutStart(context, request, response); }));} + void SetMessageAllocatorFor_RespondZoomOutStart( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(26); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondZoomOutStart( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeZoomStop() { + ::grpc::Service::MarkMethodCallback(27, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest, ::mavsdk::rpc::camera_server::ZoomStopResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* request) { return this->SubscribeZoomStop(context, request); })); + } + ~WithCallbackMethod_SubscribeZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::ZoomStopResponse>* SubscribeZoomStop( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_RespondZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondZoomStop() { + ::grpc::Service::MarkMethodCallback(28, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::mavsdk::rpc::camera_server::RespondZoomStopResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* request, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* response) { return this->RespondZoomStop(context, request, response); }));} + void SetMessageAllocatorFor_RespondZoomStop( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(28); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::mavsdk::rpc::camera_server::RespondZoomStopResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondZoomStop( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeZoomRange() { + ::grpc::Service::MarkMethodCallback(29, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest, ::mavsdk::rpc::camera_server::ZoomRangeResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* request) { return this->SubscribeZoomRange(context, request); })); + } + ~WithCallbackMethod_SubscribeZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* SubscribeZoomRange( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_RespondZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondZoomRange() { + ::grpc::Service::MarkMethodCallback(30, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* request, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* response) { return this->RespondZoomRange(context, request, response); }));} + void SetMessageAllocatorFor_RespondZoomRange( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(30); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondZoomRange( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -2159,14 +2747,150 @@ class CameraServerService final { } }; template - class WithRawMethod_SetInformation : public BaseClass { + class WithGenericMethod_SubscribeZoomInStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SetInformation() { - ::grpc::Service::MarkMethodRaw(0); + WithGenericMethod_SubscribeZoomInStart() { + ::grpc::Service::MarkMethodGeneric(23); } - ~WithRawMethod_SetInformation() override { + ~WithGenericMethod_SubscribeZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_RespondZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondZoomInStart() { + ::grpc::Service::MarkMethodGeneric(24); + } + ~WithGenericMethod_RespondZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeZoomOutStart() { + ::grpc::Service::MarkMethodGeneric(25); + } + ~WithGenericMethod_SubscribeZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_RespondZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondZoomOutStart() { + ::grpc::Service::MarkMethodGeneric(26); + } + ~WithGenericMethod_RespondZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeZoomStop() { + ::grpc::Service::MarkMethodGeneric(27); + } + ~WithGenericMethod_SubscribeZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_RespondZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondZoomStop() { + ::grpc::Service::MarkMethodGeneric(28); + } + ~WithGenericMethod_RespondZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeZoomRange() { + ::grpc::Service::MarkMethodGeneric(29); + } + ~WithGenericMethod_SubscribeZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_RespondZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondZoomRange() { + ::grpc::Service::MarkMethodGeneric(30); + } + ~WithGenericMethod_RespondZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithRawMethod_SetInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetInformation() { + ::grpc::Service::MarkMethodRaw(0); + } + ~WithRawMethod_SetInformation() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method @@ -2619,6 +3343,166 @@ class CameraServerService final { } }; template + class WithRawMethod_SubscribeZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeZoomInStart() { + ::grpc::Service::MarkMethodRaw(23); + } + ~WithRawMethod_SubscribeZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeZoomInStart(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(23, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondZoomInStart() { + ::grpc::Service::MarkMethodRaw(24); + } + ~WithRawMethod_RespondZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondZoomInStart(::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(24, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeZoomOutStart() { + ::grpc::Service::MarkMethodRaw(25); + } + ~WithRawMethod_SubscribeZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeZoomOutStart(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(25, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondZoomOutStart() { + ::grpc::Service::MarkMethodRaw(26); + } + ~WithRawMethod_RespondZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondZoomOutStart(::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(26, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeZoomStop() { + ::grpc::Service::MarkMethodRaw(27); + } + ~WithRawMethod_SubscribeZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeZoomStop(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(27, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondZoomStop() { + ::grpc::Service::MarkMethodRaw(28); + } + ~WithRawMethod_RespondZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondZoomStop(::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(28, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeZoomRange() { + ::grpc::Service::MarkMethodRaw(29); + } + ~WithRawMethod_SubscribeZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeZoomRange(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(29, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondZoomRange() { + ::grpc::Service::MarkMethodRaw(30); + } + ~WithRawMethod_RespondZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondZoomRange(::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(30, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -3125,6 +4009,182 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeZoomInStart() { + ::grpc::Service::MarkMethodRawCallback(23, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeZoomInStart(context, request); })); + } + ~WithRawCallbackMethod_SubscribeZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeZoomInStart( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_RespondZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondZoomInStart() { + ::grpc::Service::MarkMethodRawCallback(24, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondZoomInStart(context, request, response); })); + } + ~WithRawCallbackMethod_RespondZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondZoomInStart( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeZoomOutStart() { + ::grpc::Service::MarkMethodRawCallback(25, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeZoomOutStart(context, request); })); + } + ~WithRawCallbackMethod_SubscribeZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeZoomOutStart( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_RespondZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondZoomOutStart() { + ::grpc::Service::MarkMethodRawCallback(26, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondZoomOutStart(context, request, response); })); + } + ~WithRawCallbackMethod_RespondZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondZoomOutStart( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeZoomStop() { + ::grpc::Service::MarkMethodRawCallback(27, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeZoomStop(context, request); })); + } + ~WithRawCallbackMethod_SubscribeZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeZoomStop( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_RespondZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondZoomStop() { + ::grpc::Service::MarkMethodRawCallback(28, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondZoomStop(context, request, response); })); + } + ~WithRawCallbackMethod_RespondZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondZoomStop( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeZoomRange() { + ::grpc::Service::MarkMethodRawCallback(29, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeZoomRange(context, request); })); + } + ~WithRawCallbackMethod_SubscribeZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeZoomRange( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_RespondZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondZoomRange() { + ::grpc::Service::MarkMethodRawCallback(30, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondZoomRange(context, request, response); })); + } + ~WithRawCallbackMethod_RespondZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondZoomRange( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -3475,7 +4535,115 @@ 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; + template + class WithStreamedUnaryMethod_RespondZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondZoomInStart() { + ::grpc::Service::MarkMethodStreamed(24, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondZoomInStartRequest, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* streamer) { + return this->StreamedRespondZoomInStart(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondZoomInStart(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondZoomInStartRequest,::mavsdk::rpc::camera_server::RespondZoomInStartResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondZoomOutStart() { + ::grpc::Service::MarkMethodStreamed(26, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* streamer) { + return this->StreamedRespondZoomOutStart(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondZoomOutStart(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondZoomOutStartRequest,::mavsdk::rpc::camera_server::RespondZoomOutStartResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondZoomStop() { + ::grpc::Service::MarkMethodStreamed(28, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::mavsdk::rpc::camera_server::RespondZoomStopResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondZoomStopRequest, ::mavsdk::rpc::camera_server::RespondZoomStopResponse>* streamer) { + return this->StreamedRespondZoomStop(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomStopRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondZoomStop(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondZoomStopRequest,::mavsdk::rpc::camera_server::RespondZoomStopResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondZoomRange() { + ::grpc::Service::MarkMethodStreamed(30, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondZoomRangeRequest, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* streamer) { + return this->StreamedRespondZoomRange(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondZoomRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondZoomRange(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondZoomRangeRequest,::mavsdk::rpc::camera_server::RespondZoomRangeResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeTakePhoto : public BaseClass { private: @@ -3746,8 +4914,116 @@ class CameraServerService final { // replace default version of method with split streamed 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; + template + class WithSplitStreamingMethod_SubscribeZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeZoomInStart() { + ::grpc::Service::MarkMethodStreamed(23, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest, ::mavsdk::rpc::camera_server::ZoomInStartResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest, ::mavsdk::rpc::camera_server::ZoomInStartResponse>* streamer) { + return this->StreamedSubscribeZoomInStart(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomInStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeZoomInStart(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest,::mavsdk::rpc::camera_server::ZoomInStartResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeZoomOutStart() { + ::grpc::Service::MarkMethodStreamed(25, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest, ::mavsdk::rpc::camera_server::ZoomOutStartResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest, ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* streamer) { + return this->StreamedSubscribeZoomOutStart(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomOutStartResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeZoomOutStart(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest,::mavsdk::rpc::camera_server::ZoomOutStartResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeZoomStop() { + ::grpc::Service::MarkMethodStreamed(27, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest, ::mavsdk::rpc::camera_server::ZoomStopResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest, ::mavsdk::rpc::camera_server::ZoomStopResponse>* streamer) { + return this->StreamedSubscribeZoomStop(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomStopResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeZoomStop(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeZoomStopRequest,::mavsdk::rpc::camera_server::ZoomStopResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeZoomRange() { + ::grpc::Service::MarkMethodStreamed(29, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest, ::mavsdk::rpc::camera_server::ZoomRangeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest, ::mavsdk::rpc::camera_server::ZoomRangeResponse>* streamer) { + return this->StreamedSubscribeZoomRange(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ZoomRangeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeZoomRange(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest,::mavsdk::rpc::camera_server::ZoomRangeResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > > > > > > > > > SplitStreamedService; + 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..e3f7f32eb7 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,6 +24,82 @@ namespace mavsdk { namespace rpc { namespace camera_server { +inline constexpr ZoomStopResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : reserved_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ZoomStopResponse::ZoomStopResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomStopResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomStopResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomStopResponseDefaultTypeInternal() {} + union { + ZoomStopResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomStopResponseDefaultTypeInternal _ZoomStopResponse_default_instance_; + +inline constexpr ZoomRangeResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : factor_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ZoomRangeResponse::ZoomRangeResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomRangeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomRangeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomRangeResponseDefaultTypeInternal() {} + union { + ZoomRangeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomRangeResponseDefaultTypeInternal _ZoomRangeResponse_default_instance_; + +inline constexpr ZoomOutStartResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : reserved_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ZoomOutStartResponse::ZoomOutStartResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomOutStartResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomOutStartResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomOutStartResponseDefaultTypeInternal() {} + union { + ZoomOutStartResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomOutStartResponseDefaultTypeInternal _ZoomOutStartResponse_default_instance_; + +inline constexpr ZoomInStartResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : reserved_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ZoomInStartResponse::ZoomInStartResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomInStartResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomInStartResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomInStartResponseDefaultTypeInternal() {} + union { + ZoomInStartResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomInStartResponseDefaultTypeInternal _ZoomInStartResponse_default_instance_; + inline constexpr VideoStreaming::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : rtsp_uri_( @@ -65,6 +141,54 @@ struct TakePhotoResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; template +PROTOBUF_CONSTEXPR SubscribeZoomStopRequest::SubscribeZoomStopRequest(::_pbi::ConstantInitialized) {} +struct SubscribeZoomStopRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeZoomStopRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeZoomStopRequestDefaultTypeInternal() {} + union { + SubscribeZoomStopRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeZoomStopRequestDefaultTypeInternal _SubscribeZoomStopRequest_default_instance_; + template +PROTOBUF_CONSTEXPR SubscribeZoomRangeRequest::SubscribeZoomRangeRequest(::_pbi::ConstantInitialized) {} +struct SubscribeZoomRangeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeZoomRangeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeZoomRangeRequestDefaultTypeInternal() {} + union { + SubscribeZoomRangeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeZoomRangeRequestDefaultTypeInternal _SubscribeZoomRangeRequest_default_instance_; + template +PROTOBUF_CONSTEXPR SubscribeZoomOutStartRequest::SubscribeZoomOutStartRequest(::_pbi::ConstantInitialized) {} +struct SubscribeZoomOutStartRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeZoomOutStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeZoomOutStartRequestDefaultTypeInternal() {} + union { + SubscribeZoomOutStartRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeZoomOutStartRequestDefaultTypeInternal _SubscribeZoomOutStartRequest_default_instance_; + template +PROTOBUF_CONSTEXPR SubscribeZoomInStartRequest::SubscribeZoomInStartRequest(::_pbi::ConstantInitialized) {} +struct SubscribeZoomInStartRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeZoomInStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeZoomInStartRequestDefaultTypeInternal() {} + union { + SubscribeZoomInStartRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeZoomInStartRequestDefaultTypeInternal _SubscribeZoomInStartRequest_default_instance_; + template PROTOBUF_CONSTEXPR SubscribeTakePhotoRequest::SubscribeTakePhotoRequest(::_pbi::ConstantInitialized) {} struct SubscribeTakePhotoRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR SubscribeTakePhotoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} @@ -344,6 +468,82 @@ struct SetInProgressRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetInProgressRequestDefaultTypeInternal _SetInProgressRequest_default_instance_; +inline constexpr RespondZoomStopRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : zoom_stop_feedback_{static_cast< ::mavsdk::rpc::camera_server::CameraFeedback >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR RespondZoomStopRequest::RespondZoomStopRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RespondZoomStopRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondZoomStopRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondZoomStopRequestDefaultTypeInternal() {} + union { + RespondZoomStopRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondZoomStopRequestDefaultTypeInternal _RespondZoomStopRequest_default_instance_; + +inline constexpr RespondZoomRangeRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : zoom_range_feedback_{static_cast< ::mavsdk::rpc::camera_server::CameraFeedback >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR RespondZoomRangeRequest::RespondZoomRangeRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RespondZoomRangeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondZoomRangeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondZoomRangeRequestDefaultTypeInternal() {} + union { + RespondZoomRangeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondZoomRangeRequestDefaultTypeInternal _RespondZoomRangeRequest_default_instance_; + +inline constexpr RespondZoomOutStartRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : zoom_out_start_feedback_{static_cast< ::mavsdk::rpc::camera_server::CameraFeedback >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR RespondZoomOutStartRequest::RespondZoomOutStartRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RespondZoomOutStartRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondZoomOutStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondZoomOutStartRequestDefaultTypeInternal() {} + union { + RespondZoomOutStartRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondZoomOutStartRequestDefaultTypeInternal _RespondZoomOutStartRequest_default_instance_; + +inline constexpr RespondZoomInStartRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : zoom_in_start_feedback_{static_cast< ::mavsdk::rpc::camera_server::CameraFeedback >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR RespondZoomInStartRequest::RespondZoomInStartRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RespondZoomInStartRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondZoomInStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondZoomInStartRequestDefaultTypeInternal() {} + union { + RespondZoomInStartRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondZoomInStartRequestDefaultTypeInternal _RespondZoomInStartRequest_default_instance_; + inline constexpr RespondStopVideoStreamingRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : stop_video_streaming_feedback_{static_cast< ::mavsdk::rpc::camera_server::CameraFeedback >(0)}, @@ -756,6 +956,82 @@ struct SetInProgressResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetInProgressResponseDefaultTypeInternal _SetInProgressResponse_default_instance_; +inline constexpr RespondZoomStopResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_server_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR RespondZoomStopResponse::RespondZoomStopResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RespondZoomStopResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondZoomStopResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondZoomStopResponseDefaultTypeInternal() {} + union { + RespondZoomStopResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondZoomStopResponseDefaultTypeInternal _RespondZoomStopResponse_default_instance_; + +inline constexpr RespondZoomRangeResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_server_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR RespondZoomRangeResponse::RespondZoomRangeResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RespondZoomRangeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondZoomRangeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondZoomRangeResponseDefaultTypeInternal() {} + union { + RespondZoomRangeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondZoomRangeResponseDefaultTypeInternal _RespondZoomRangeResponse_default_instance_; + +inline constexpr RespondZoomOutStartResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_server_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR RespondZoomOutStartResponse::RespondZoomOutStartResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RespondZoomOutStartResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondZoomOutStartResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondZoomOutStartResponseDefaultTypeInternal() {} + union { + RespondZoomOutStartResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondZoomOutStartResponseDefaultTypeInternal _RespondZoomOutStartResponse_default_instance_; + +inline constexpr RespondZoomInStartResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_server_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR RespondZoomInStartResponse::RespondZoomInStartResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RespondZoomInStartResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondZoomInStartResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondZoomInStartResponseDefaultTypeInternal() {} + union { + RespondZoomInStartResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondZoomInStartResponseDefaultTypeInternal _RespondZoomInStartResponse_default_instance_; + inline constexpr RespondTakePhotoResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -1034,7 +1310,7 @@ 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 ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[70]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; @@ -1469,133 +1745,277 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondResetSettingsResponse, _impl_.camera_server_result_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest, _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::Information, _impl_.vendor_name_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.model_name_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.firmware_version_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.focal_length_mm_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.horizontal_sensor_size_mm_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.vertical_sensor_size_mm_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.horizontal_resolution_px_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.vertical_resolution_px_), - 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_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreaming, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::ZoomInStartResponse, _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::ZoomInStartResponse, _impl_.reserved_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomInStartRequest, _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::Position, _impl_.latitude_deg_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _impl_.longitude_deg_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _impl_.absolute_altitude_m_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _impl_.relative_altitude_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomInStartRequest, _impl_.zoom_in_start_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomInStartResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomInStartResponse, _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::RespondZoomInStartResponse, _impl_.camera_server_result_), + 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest, _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::Quaternion, _impl_.w_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, _impl_.x_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, _impl_.y_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, _impl_.z_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _internal_metadata_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::ZoomOutStartResponse, _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::CaptureInfo, _impl_.position_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.attitude_quaternion_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.time_utc_us_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.is_success_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.index_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.file_url_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::ZoomOutStartResponse, _impl_.reserved_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomOutStartRequest, _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::RespondZoomOutStartRequest, _impl_.zoom_out_start_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomOutStartResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomOutStartResponse, _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::RespondZoomOutStartResponse, _impl_.camera_server_result_), 0, - 1, - ~0u, - ~0u, - ~0u, - ~0u, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CameraServerResult, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeZoomStopRequest, _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::CameraServerResult, _impl_.result_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CameraServerResult, _impl_.result_str_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::ZoomStopResponse, _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::StorageInformation, _impl_.used_storage_mib_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.available_storage_mib_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.total_storage_mib_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_status_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_id_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_type_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.read_speed_mib_s_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.write_speed_mib_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::ZoomStopResponse, _impl_.reserved_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomStopRequest, _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::CaptureStatus, _impl_.image_interval_s_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.recording_time_s_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.available_capacity_mib_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_status_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.video_status_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_count_), -}; - -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)}, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomStopRequest, _impl_.zoom_stop_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomStopResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomStopResponse, _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::RespondZoomStopResponse, _impl_.camera_server_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest, _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) + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::ZoomRangeResponse, _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::ZoomRangeResponse, _impl_.factor_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomRangeRequest, _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::RespondZoomRangeRequest, _impl_.zoom_range_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomRangeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondZoomRangeResponse, _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::RespondZoomRangeResponse, _impl_.camera_server_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _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::Information, _impl_.vendor_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.model_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.firmware_version_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.focal_length_mm_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.horizontal_sensor_size_mm_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.vertical_sensor_size_mm_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.horizontal_resolution_px_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.vertical_resolution_px_), + 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_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreaming, _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_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _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::Position, _impl_.latitude_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _impl_.longitude_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _impl_.absolute_altitude_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _impl_.relative_altitude_m_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, _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::Quaternion, _impl_.w_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, _impl_.x_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, _impl_.y_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, _impl_.z_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _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::CaptureInfo, _impl_.position_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.attitude_quaternion_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.time_utc_us_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.is_success_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.index_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _impl_.file_url_), + 0, + 1, + ~0u, + ~0u, + ~0u, + ~0u, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CameraServerResult, _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::CameraServerResult, _impl_.result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CameraServerResult, _impl_.result_str_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _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::StorageInformation, _impl_.used_storage_mib_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.available_storage_mib_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.total_storage_mib_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_status_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_type_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.read_speed_mib_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.write_speed_mib_s_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _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::CaptureStatus, _impl_.image_interval_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.recording_time_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.available_capacity_mib_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_status_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.video_status_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_count_), +}; + +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)}, @@ -1631,14 +2051,30 @@ static const ::_pbi::MigrationSchema {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)}, + {428, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeZoomInStartRequest)}, + {436, -1, -1, sizeof(::mavsdk::rpc::camera_server::ZoomInStartResponse)}, + {445, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondZoomInStartRequest)}, + {454, 463, -1, sizeof(::mavsdk::rpc::camera_server::RespondZoomInStartResponse)}, + {464, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest)}, + {472, -1, -1, sizeof(::mavsdk::rpc::camera_server::ZoomOutStartResponse)}, + {481, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondZoomOutStartRequest)}, + {490, 499, -1, sizeof(::mavsdk::rpc::camera_server::RespondZoomOutStartResponse)}, + {500, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeZoomStopRequest)}, + {508, -1, -1, sizeof(::mavsdk::rpc::camera_server::ZoomStopResponse)}, + {517, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondZoomStopRequest)}, + {526, 535, -1, sizeof(::mavsdk::rpc::camera_server::RespondZoomStopResponse)}, + {536, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeZoomRangeRequest)}, + {544, -1, -1, sizeof(::mavsdk::rpc::camera_server::ZoomRangeResponse)}, + {553, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondZoomRangeRequest)}, + {562, 571, -1, sizeof(::mavsdk::rpc::camera_server::RespondZoomRangeResponse)}, + {572, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + {591, -1, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreaming)}, + {601, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + {613, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + {625, 639, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + {645, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + {655, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, + {671, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -1688,6 +2124,22 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_ResetSettingsResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondResetSettingsRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondResetSettingsResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeZoomInStartRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_ZoomInStartResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondZoomInStartRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondZoomInStartResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeZoomOutStartRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_ZoomOutStartResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondZoomOutStartRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondZoomOutStartResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeZoomStopRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_ZoomStopResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondZoomStopRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondZoomStopResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeZoomRangeRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_ZoomRangeResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondZoomRangeRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondZoomRangeResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, &::mavsdk::rpc::camera_server::_VideoStreaming_default_instance_._instance, &::mavsdk::rpc::camera_server::_Position_default_instance_._instance, @@ -1791,149 +2243,203 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "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" + "mera_server.CameraServerResult\"\035\n\033Subscr" + "ibeZoomInStartRequest\"\'\n\023ZoomInStartResp" + "onse\022\020\n\010reserved\030\001 \001(\005\"e\n\031RespondZoomInS" + "tartRequest\022H\n\026zoom_in_start_feedback\030\001 " + "\001(\0162(.mavsdk.rpc.camera_server.CameraFee" + "dback\"h\n\032RespondZoomInStartResponse\022J\n\024c" + "amera_server_result\030\001 \001(\0132,.mavsdk.rpc.c" + "amera_server.CameraServerResult\"\036\n\034Subsc" + "ribeZoomOutStartRequest\"(\n\024ZoomOutStartR" + "esponse\022\020\n\010reserved\030\001 \001(\005\"g\n\032RespondZoom" + "OutStartRequest\022I\n\027zoom_out_start_feedba" + "ck\030\001 \001(\0162(.mavsdk.rpc.camera_server.Came" + "raFeedback\"i\n\033RespondZoomOutStartRespons" + "e\022J\n\024camera_server_result\030\001 \001(\0132,.mavsdk" + ".rpc.camera_server.CameraServerResult\"\032\n" + "\030SubscribeZoomStopRequest\"$\n\020ZoomStopRes" + "ponse\022\020\n\010reserved\030\001 \001(\005\"^\n\026RespondZoomSt" + "opRequest\022D\n\022zoom_stop_feedback\030\001 \001(\0162(." + "mavsdk.rpc.camera_server.CameraFeedback\"" + "e\n\027RespondZoomStopResponse\022J\n\024camera_ser" + "ver_result\030\001 \001(\0132,.mavsdk.rpc.camera_ser" + "ver.CameraServerResult\"\033\n\031SubscribeZoomR" + "angeRequest\"#\n\021ZoomRangeResponse\022\016\n\006fact" + "or\030\001 \001(\002\"`\n\027RespondZoomRangeRequest\022E\n\023z" + "oom_range_feedback\030\001 \001(\0162(.mavsdk.rpc.ca" + "mera_server.CameraFeedback\"f\n\030RespondZoo" + "mRangeResponse\022J\n\024camera_server_result\030\001" + " \001(\0132,.mavsdk.rpc.camera_server.CameraSe" + "rverResult\"\276\002\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\";\n\016VideoStreaming\022\027\n\017has_rts" + "p_server\030\001 \001(\010\022\020\n\010rtsp_uri\030\002 \001(\t\"q\n\010Posi" + "tion\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\nQuaternio" + "n\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_server.Position\022A\n\023a" + "ttitude_quaternion\030\002 \001(\0132$.mavsdk.rpc.ca" + "mera_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\022CameraServerResult\022" + "C\n\006result\030\001 \001(\01623.mavsdk.rpc.camera_serv" + "er.CameraServerResult.Result\022\022\n\nresult_s" + "tr\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_PROGRES" + "S\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_SY" + "STEM\020\010\"\214\005\n\022StorageInformation\022\030\n\020used_st" + "orage_mib\030\001 \001(\002\022\035\n\025available_storage_mib" + "\030\002 \001(\002\022\031\n\021total_storage_mib\030\003 \001(\002\022R\n\016sto" + "rage_status\030\004 \001(\0162:.mavsdk.rpc.camera_se" + "rver.StorageInformation.StorageStatus\022\022\n" + "\nstorage_id\030\005 \001(\r\022N\n\014storage_type\030\006 \001(\0162" + "8.mavsdk.rpc.camera_server.StorageInform" + "ation.StorageType\022\030\n\020read_speed_mib_s\030\007 " + "\001(\002\022\031\n\021write_speed_mib_s\030\010 \001(\002\"\221\001\n\rStora" + "geStatus\022 \n\034STORAGE_STATUS_NOT_AVAILABLE" + "\020\000\022\036\n\032STORAGE_STATUS_UNFORMATTED\020\001\022\034\n\030ST" + "ORAGE_STATUS_FORMATTED\020\002\022 \n\034STORAGE_STAT" + "US_NOT_SUPPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024ST" + "ORAGE_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\017STORAGE_TYPE_HD\020\007\022\027\n\022" + "STORAGE_TYPE_OTHER\020\376\001\"\356\003\n\rCaptureStatus\022" + "\030\n\020image_interval_s\030\001 \001(\002\022\030\n\020recording_t" + "ime_s\030\002 \001(\002\022\036\n\026available_capacity_mib\030\003 " + "\001(\002\022I\n\014image_status\030\004 \001(\01623.mavsdk.rpc.c" + "amera_server.CaptureStatus.ImageStatus\022I" + "\n\014video_status\030\005 \001(\01623.mavsdk.rpc.camera" + "_server.CaptureStatus.VideoStatus\022\023\n\013ima" + "ge_count\030\006 \001(\005\"\221\001\n\013ImageStatus\022\025\n\021IMAGE_" + "STATUS_IDLE\020\000\022$\n IMAGE_STATUS_CAPTURE_IN" + "_PROGRESS\020\001\022\036\n\032IMAGE_STATUS_INTERVAL_IDL" + "E\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_CAPTURE_IN_PROGRESS\020\001*{" + "\n\016CameraFeedback\022\033\n\027CAMERA_FEEDBACK_UNKN" + "OWN\020\000\022\026\n\022CAMERA_FEEDBACK_OK\020\001\022\030\n\024CAMERA_" + "FEEDBACK_BUSY\020\002\022\032\n\026CAMERA_FEEDBACK_FAILE" + "D\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PH" + "OTO\020\001\022\016\n\nMODE_VIDEO\020\0022\257!\n\023CameraServerSe" + "rvice\022y\n\016SetInformation\022/.mavsdk.rpc.cam" + "era_server.SetInformationRequest\0320.mavsd" + "k.rpc.camera_server.SetInformationRespon" + "se\"\004\200\265\030\001\022\202\001\n\021SetVideoStreaming\0222.mavsdk." + "rpc.camera_server.SetVideoStreamingReque" + "st\0323.mavsdk.rpc.camera_server.SetVideoSt" + "reamingResponse\"\004\200\265\030\001\022v\n\rSetInProgress\022." + ".mavsdk.rpc.camera_server.SetInProgressR" + "equest\032/.mavsdk.rpc.camera_server.SetInP" + "rogressResponse\"\004\200\265\030\001\022~\n\022SubscribeTakePh" + "oto\0223.mavsdk.rpc.camera_server.Subscribe" + "TakePhotoRequest\032+.mavsdk.rpc.camera_ser" + "ver.TakePhotoResponse\"\004\200\265\030\0000\001\022\177\n\020Respond" + "TakePhoto\0221.mavsdk.rpc.camera_server.Res" + "pondTakePhotoRequest\0322.mavsdk.rpc.camera" + "_server.RespondTakePhotoResponse\"\004\200\265\030\001\022\201" + "\001\n\023SubscribeStartVideo\0224.mavsdk.rpc.came" + "ra_server.SubscribeStartVideoRequest\032,.m" + "avsdk.rpc.camera_server.StartVideoRespon" + "se\"\004\200\265\030\0000\001\022\202\001\n\021RespondStartVideo\0222.mavsd" + "k.rpc.camera_server.RespondStartVideoReq" + "uest\0323.mavsdk.rpc.camera_server.RespondS" + "tartVideoResponse\"\004\200\265\030\001\022~\n\022SubscribeStop" + "Video\0223.mavsdk.rpc.camera_server.Subscri" + "beStopVideoRequest\032+.mavsdk.rpc.camera_s" + "erver.StopVideoResponse\"\004\200\265\030\0000\001\022\177\n\020Respo" + "ndStopVideo\0221.mavsdk.rpc.camera_server.R" + "espondStopVideoRequest\0322.mavsdk.rpc.came" + "ra_server.RespondStopVideoResponse\"\004\200\265\030\001" + "\022\234\001\n\034SubscribeStartVideoStreaming\022=.mavs" + "dk.rpc.camera_server.SubscribeStartVideo" + "StreamingRequest\0325.mavsdk.rpc.camera_ser" + "ver.StartVideoStreamingResponse\"\004\200\265\030\0000\001\022" + "\235\001\n\032RespondStartVideoStreaming\022;.mavsdk." + "rpc.camera_server.RespondStartVideoStrea" + "mingRequest\032<.mavsdk.rpc.camera_server.R" + "espondStartVideoStreamingResponse\"\004\200\265\030\001\022" + "\231\001\n\033SubscribeStopVideoStreaming\022<.mavsdk" + ".rpc.camera_server.SubscribeStopVideoStr" + "eamingRequest\0324.mavsdk.rpc.camera_server" + ".StopVideoStreamingResponse\"\004\200\265\030\0000\001\022\232\001\n\031" + "RespondStopVideoStreaming\022:.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" + "quest\032;.mavsdk.rpc.camera_server.Respond" + "StopVideoStreamingResponse\"\004\200\265\030\001\022x\n\020Subs" + "cribeSetMode\0221.mavsdk.rpc.camera_server." + "SubscribeSetModeRequest\032).mavsdk.rpc.cam" + "era_server.SetModeResponse\"\004\200\265\030\0000\001\022y\n\016Re" + "spondSetMode\022/.mavsdk.rpc.camera_server." + "RespondSetModeRequest\0320.mavsdk.rpc.camer" + "a_server.RespondSetModeResponse\"\004\200\265\030\001\022\231\001" + "\n\033SubscribeStorageInformation\022<.mavsdk.r" + "pc.camera_server.SubscribeStorageInforma" + "tionRequest\0324.mavsdk.rpc.camera_server.S" + "torageInformationResponse\"\004\200\265\030\0000\001\022\232\001\n\031Re" + "spondStorageInformation\022:.mavsdk.rpc.cam" + "era_server.RespondStorageInformationRequ" + "est\032;.mavsdk.rpc.camera_server.RespondSt" + "orageInformationResponse\"\004\200\265\030\001\022\212\001\n\026Subsc" + "ribeCaptureStatus\0227.mavsdk.rpc.camera_se" + "rver.SubscribeCaptureStatusRequest\032/.mav" + "sdk.rpc.camera_server.CaptureStatusRespo" + "nse\"\004\200\265\030\0000\001\022\213\001\n\024RespondCaptureStatus\0225.m" + "avsdk.rpc.camera_server.RespondCaptureSt" + "atusRequest\0326.mavsdk.rpc.camera_server.R" + "espondCaptureStatusResponse\"\004\200\265\030\001\022\212\001\n\026Su" + "bscribeFormatStorage\0227.mavsdk.rpc.camera" + "_server.SubscribeFormatStorageRequest\032/." + "mavsdk.rpc.camera_server.FormatStorageRe" + "sponse\"\004\200\265\030\0000\001\022\213\001\n\024RespondFormatStorage\022" + "5.mavsdk.rpc.camera_server.RespondFormat" + "StorageRequest\0326.mavsdk.rpc.camera_serve" + "r.RespondFormatStorageResponse\"\004\200\265\030\001\022\212\001\n" + "\026SubscribeResetSettings\0227.mavsdk.rpc.cam" + "era_server.SubscribeResetSettingsRequest" + "\032/.mavsdk.rpc.camera_server.ResetSetting" + "sResponse\"\004\200\265\030\0000\001\022\213\001\n\024RespondResetSettin" + "gs\0225.mavsdk.rpc.camera_server.RespondRes" + "etSettingsRequest\0326.mavsdk.rpc.camera_se" + "rver.RespondResetSettingsResponse\"\004\200\265\030\001\022" + "\204\001\n\024SubscribeZoomInStart\0225.mavsdk.rpc.ca" + "mera_server.SubscribeZoomInStartRequest\032" + "-.mavsdk.rpc.camera_server.ZoomInStartRe" + "sponse\"\004\200\265\030\0000\001\022\205\001\n\022RespondZoomInStart\0223." + "mavsdk.rpc.camera_server.RespondZoomInSt" + "artRequest\0324.mavsdk.rpc.camera_server.Re" + "spondZoomInStartResponse\"\004\200\265\030\001\022\207\001\n\025Subsc" + "ribeZoomOutStart\0226.mavsdk.rpc.camera_ser" + "ver.SubscribeZoomOutStartRequest\032..mavsd" + "k.rpc.camera_server.ZoomOutStartResponse" + "\"\004\200\265\030\0000\001\022\210\001\n\023RespondZoomOutStart\0224.mavsd" + "k.rpc.camera_server.RespondZoomOutStartR" + "equest\0325.mavsdk.rpc.camera_server.Respon" + "dZoomOutStartResponse\"\004\200\265\030\001\022{\n\021Subscribe" + "ZoomStop\0222.mavsdk.rpc.camera_server.Subs" + "cribeZoomStopRequest\032*.mavsdk.rpc.camera" + "_server.ZoomStopResponse\"\004\200\265\030\0000\001\022|\n\017Resp" + "ondZoomStop\0220.mavsdk.rpc.camera_server.R" + "espondZoomStopRequest\0321.mavsdk.rpc.camer" + "a_server.RespondZoomStopResponse\"\004\200\265\030\001\022~" + "\n\022SubscribeZoomRange\0223.mavsdk.rpc.camera" + "_server.SubscribeZoomRangeRequest\032+.mavs" + "dk.rpc.camera_server.ZoomRangeResponse\"\004" + "\200\265\030\0000\001\022\177\n\020RespondZoomRange\0221.mavsdk.rpc." + "camera_server.RespondZoomRangeRequest\0322." + "mavsdk.rpc.camera_server.RespondZoomRang" + "eResponse\"\004\200\265\030\001B,\n\027io.mavsdk.camera_serv" + "erB\021CameraServerProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -1943,13 +2449,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, + 11589, 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, + 70, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -8454,17 +8960,2345 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> RespondFormatStorageRequest::_table_ = 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_RespondFormatStorageRequest_default_instance_._instance, + &_RespondFormatStorageRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RespondFormatStorageRequest, _impl_.format_storage_feedback_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(RespondFormatStorageRequest, _impl_.format_storage_feedback_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; + {PROTOBUF_FIELD_OFFSET(RespondFormatStorageRequest, _impl_.format_storage_feedback_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* RespondFormatStorageRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; + if (this->_internal_format_storage_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_format_storage_feedback(), 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.RespondFormatStorageRequest) + return target; +} + +::size_t RespondFormatStorageRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) + ::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.CameraFeedback format_storage_feedback = 1; + if (this->_internal_format_storage_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_format_storage_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RespondFormatStorageRequest::_class_data_ = { + RespondFormatStorageRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RespondFormatStorageRequest::GetClassData() const { + return &_class_data_; +} + +void RespondFormatStorageRequest::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.RespondFormatStorageRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_format_storage_feedback() != 0) { + _this->_internal_set_format_storage_feedback(from._internal_format_storage_feedback()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondFormatStorageRequest::CopyFrom(const RespondFormatStorageRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RespondFormatStorageRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RespondFormatStorageRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RespondFormatStorageRequest::InternalSwap(RespondFormatStorageRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.format_storage_feedback_, other->_impl_.format_storage_feedback_); +} + +::google::protobuf::Metadata RespondFormatStorageRequest::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[40]); +} +// =================================================================== + +class RespondFormatStorageResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondFormatStorageResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondFormatStorageResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& RespondFormatStorageResponse::_Internal::camera_server_result(const RespondFormatStorageResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondFormatStorageResponse::RespondFormatStorageResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) +} +inline PROTOBUF_NDEBUG_INLINE RespondFormatStorageResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +RespondFormatStorageResponse::RespondFormatStorageResponse( + ::google::protobuf::Arena* arena, + const RespondFormatStorageResponse& from) + : ::google::protobuf::Message(arena) { + RespondFormatStorageResponse* 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_.camera_server_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(arena, *from._impl_.camera_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) +} +inline PROTOBUF_NDEBUG_INLINE RespondFormatStorageResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RespondFormatStorageResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_server_result_ = {}; +} +RespondFormatStorageResponse::~RespondFormatStorageResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RespondFormatStorageResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_server_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RespondFormatStorageResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + 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_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RespondFormatStorageResponse::_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<0, 1, 1, 0, 2> RespondFormatStorageResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(RespondFormatStorageResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_RespondFormatStorageResponse_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(RespondFormatStorageResponse, _impl_.camera_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + {PROTOBUF_FIELD_OFFSET(RespondFormatStorageResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::CameraServerResult>()}, + }}, {{ + }}, +}; + +::uint8_t* RespondFormatStorageResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + 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.RespondFormatStorageResponse) + return target; +} + +::size_t RespondFormatStorageResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + ::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.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RespondFormatStorageResponse::_class_data_ = { + RespondFormatStorageResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RespondFormatStorageResponse::GetClassData() const { + return &_class_data_; +} + +void RespondFormatStorageResponse::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.RespondFormatStorageResponse) + 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_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondFormatStorageResponse::CopyFrom(const RespondFormatStorageResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RespondFormatStorageResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RespondFormatStorageResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RespondFormatStorageResponse::InternalSwap(RespondFormatStorageResponse* 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 RespondFormatStorageResponse::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[41]); +} +// =================================================================== + +class SubscribeResetSettingsRequest::_Internal { + public: +}; + +SubscribeResetSettingsRequest::SubscribeResetSettingsRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) +} +SubscribeResetSettingsRequest::SubscribeResetSettingsRequest( + ::google::protobuf::Arena* arena, + const SubscribeResetSettingsRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeResetSettingsRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeResetSettingsRequest::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[42]); +} +// =================================================================== + +class ResetSettingsResponse::_Internal { + public: +}; + +ResetSettingsResponse::ResetSettingsResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.ResetSettingsResponse) +} +ResetSettingsResponse::ResetSettingsResponse( + ::google::protobuf::Arena* arena, const ResetSettingsResponse& from) + : ResetSettingsResponse(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ResetSettingsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.reserved_ = {}; +} +ResetSettingsResponse::~ResetSettingsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.ResetSettingsResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ResetSettingsResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ResetSettingsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + 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_.reserved_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ResetSettingsResponse::_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<0, 1, 0, 0, 2> ResetSettingsResponse::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ResetSettingsResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 reserved = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ResetSettingsResponse, _impl_.reserved_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_.reserved_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 reserved = 1; + {PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_.reserved_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ResetSettingsResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_reserved(), 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.ResetSettingsResponse) + return target; +} + +::size_t ResetSettingsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_reserved()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ResetSettingsResponse::_class_data_ = { + ResetSettingsResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ResetSettingsResponse::GetClassData() const { + return &_class_data_; +} + +void ResetSettingsResponse::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.ResetSettingsResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_reserved() != 0) { + _this->_internal_set_reserved(from._internal_reserved()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ResetSettingsResponse::CopyFrom(const ResetSettingsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ResetSettingsResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ResetSettingsResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.reserved_, other->_impl_.reserved_); +} + +::google::protobuf::Metadata ResetSettingsResponse::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[43]); +} +// =================================================================== + +class RespondResetSettingsRequest::_Internal { + public: +}; + +RespondResetSettingsRequest::RespondResetSettingsRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondResetSettingsRequest) +} +RespondResetSettingsRequest::RespondResetSettingsRequest( + ::google::protobuf::Arena* arena, const RespondResetSettingsRequest& from) + : RespondResetSettingsRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE RespondResetSettingsRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RespondResetSettingsRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.reset_settings_feedback_ = {}; +} +RespondResetSettingsRequest::~RespondResetSettingsRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RespondResetSettingsRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RespondResetSettingsRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + 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_.reset_settings_feedback_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RespondResetSettingsRequest::_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<0, 1, 0, 0, 2> RespondResetSettingsRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_RespondResetSettingsRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RespondResetSettingsRequest, _impl_.reset_settings_feedback_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(RespondResetSettingsRequest, _impl_.reset_settings_feedback_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; + {PROTOBUF_FIELD_OFFSET(RespondResetSettingsRequest, _impl_.reset_settings_feedback_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* RespondResetSettingsRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; + if (this->_internal_reset_settings_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_reset_settings_feedback(), 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.RespondResetSettingsRequest) + return target; +} + +::size_t RespondResetSettingsRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + ::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.CameraFeedback reset_settings_feedback = 1; + if (this->_internal_reset_settings_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_reset_settings_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RespondResetSettingsRequest::_class_data_ = { + RespondResetSettingsRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RespondResetSettingsRequest::GetClassData() const { + return &_class_data_; +} + +void RespondResetSettingsRequest::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.RespondResetSettingsRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_reset_settings_feedback() != 0) { + _this->_internal_set_reset_settings_feedback(from._internal_reset_settings_feedback()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondResetSettingsRequest::CopyFrom(const RespondResetSettingsRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RespondResetSettingsRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RespondResetSettingsRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RespondResetSettingsRequest::InternalSwap(RespondResetSettingsRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.reset_settings_feedback_, other->_impl_.reset_settings_feedback_); +} + +::google::protobuf::Metadata RespondResetSettingsRequest::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[44]); +} +// =================================================================== + +class RespondResetSettingsResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondResetSettingsResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondResetSettingsResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& RespondResetSettingsResponse::_Internal::camera_server_result(const RespondResetSettingsResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondResetSettingsResponse::RespondResetSettingsResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) +} +inline PROTOBUF_NDEBUG_INLINE RespondResetSettingsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +RespondResetSettingsResponse::RespondResetSettingsResponse( + ::google::protobuf::Arena* arena, + const RespondResetSettingsResponse& from) + : ::google::protobuf::Message(arena) { + RespondResetSettingsResponse* 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_.camera_server_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(arena, *from._impl_.camera_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) +} +inline PROTOBUF_NDEBUG_INLINE RespondResetSettingsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RespondResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_server_result_ = {}; +} +RespondResetSettingsResponse::~RespondResetSettingsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RespondResetSettingsResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_server_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RespondResetSettingsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + 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_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RespondResetSettingsResponse::_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<0, 1, 1, 0, 2> RespondResetSettingsResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(RespondResetSettingsResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_RespondResetSettingsResponse_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(RespondResetSettingsResponse, _impl_.camera_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + {PROTOBUF_FIELD_OFFSET(RespondResetSettingsResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::CameraServerResult>()}, + }}, {{ + }}, +}; + +::uint8_t* RespondResetSettingsResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + 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.RespondResetSettingsResponse) + return target; +} + +::size_t RespondResetSettingsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + ::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.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RespondResetSettingsResponse::_class_data_ = { + RespondResetSettingsResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RespondResetSettingsResponse::GetClassData() const { + return &_class_data_; +} + +void RespondResetSettingsResponse::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.RespondResetSettingsResponse) + 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_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondResetSettingsResponse::CopyFrom(const RespondResetSettingsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RespondResetSettingsResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RespondResetSettingsResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RespondResetSettingsResponse::InternalSwap(RespondResetSettingsResponse* 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 RespondResetSettingsResponse::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[45]); +} +// =================================================================== + +class SubscribeZoomInStartRequest::_Internal { + public: +}; + +SubscribeZoomInStartRequest::SubscribeZoomInStartRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeZoomInStartRequest) +} +SubscribeZoomInStartRequest::SubscribeZoomInStartRequest( + ::google::protobuf::Arena* arena, + const SubscribeZoomInStartRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeZoomInStartRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeZoomInStartRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeZoomInStartRequest::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[46]); +} +// =================================================================== + +class ZoomInStartResponse::_Internal { + public: +}; + +ZoomInStartResponse::ZoomInStartResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.ZoomInStartResponse) +} +ZoomInStartResponse::ZoomInStartResponse( + ::google::protobuf::Arena* arena, const ZoomInStartResponse& from) + : ZoomInStartResponse(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ZoomInStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomInStartResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.reserved_ = {}; +} +ZoomInStartResponse::~ZoomInStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.ZoomInStartResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomInStartResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomInStartResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.ZoomInStartResponse) + 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_.reserved_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomInStartResponse::_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<0, 1, 0, 0, 2> ZoomInStartResponse::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ZoomInStartResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 reserved = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ZoomInStartResponse, _impl_.reserved_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_.reserved_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 reserved = 1; + {PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_.reserved_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ZoomInStartResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.ZoomInStartResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_reserved(), 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.ZoomInStartResponse) + return target; +} + +::size_t ZoomInStartResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.ZoomInStartResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_reserved()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomInStartResponse::_class_data_ = { + ZoomInStartResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomInStartResponse::GetClassData() const { + return &_class_data_; +} + +void ZoomInStartResponse::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.ZoomInStartResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_reserved() != 0) { + _this->_internal_set_reserved(from._internal_reserved()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomInStartResponse::CopyFrom(const ZoomInStartResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.ZoomInStartResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomInStartResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomInStartResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomInStartResponse::InternalSwap(ZoomInStartResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.reserved_, other->_impl_.reserved_); +} + +::google::protobuf::Metadata ZoomInStartResponse::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 RespondZoomInStartRequest::_Internal { + public: +}; + +RespondZoomInStartRequest::RespondZoomInStartRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondZoomInStartRequest) +} +RespondZoomInStartRequest::RespondZoomInStartRequest( + ::google::protobuf::Arena* arena, const RespondZoomInStartRequest& from) + : RespondZoomInStartRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE RespondZoomInStartRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RespondZoomInStartRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.zoom_in_start_feedback_ = {}; +} +RespondZoomInStartRequest::~RespondZoomInStartRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondZoomInStartRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RespondZoomInStartRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RespondZoomInStartRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondZoomInStartRequest) + 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_.zoom_in_start_feedback_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RespondZoomInStartRequest::_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<0, 1, 0, 0, 2> RespondZoomInStartRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_RespondZoomInStartRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera_server.CameraFeedback zoom_in_start_feedback = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RespondZoomInStartRequest, _impl_.zoom_in_start_feedback_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(RespondZoomInStartRequest, _impl_.zoom_in_start_feedback_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera_server.CameraFeedback zoom_in_start_feedback = 1; + {PROTOBUF_FIELD_OFFSET(RespondZoomInStartRequest, _impl_.zoom_in_start_feedback_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* RespondZoomInStartRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondZoomInStartRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback zoom_in_start_feedback = 1; + if (this->_internal_zoom_in_start_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_zoom_in_start_feedback(), 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.RespondZoomInStartRequest) + return target; +} + +::size_t RespondZoomInStartRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondZoomInStartRequest) + ::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.CameraFeedback zoom_in_start_feedback = 1; + if (this->_internal_zoom_in_start_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_zoom_in_start_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RespondZoomInStartRequest::_class_data_ = { + RespondZoomInStartRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RespondZoomInStartRequest::GetClassData() const { + return &_class_data_; +} + +void RespondZoomInStartRequest::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.RespondZoomInStartRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_zoom_in_start_feedback() != 0) { + _this->_internal_set_zoom_in_start_feedback(from._internal_zoom_in_start_feedback()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondZoomInStartRequest::CopyFrom(const RespondZoomInStartRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondZoomInStartRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RespondZoomInStartRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RespondZoomInStartRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RespondZoomInStartRequest::InternalSwap(RespondZoomInStartRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.zoom_in_start_feedback_, other->_impl_.zoom_in_start_feedback_); +} + +::google::protobuf::Metadata RespondZoomInStartRequest::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 RespondZoomInStartResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondZoomInStartResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondZoomInStartResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomInStartResponse::_Internal::camera_server_result(const RespondZoomInStartResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondZoomInStartResponse::RespondZoomInStartResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondZoomInStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE RespondZoomInStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +RespondZoomInStartResponse::RespondZoomInStartResponse( + ::google::protobuf::Arena* arena, + const RespondZoomInStartResponse& from) + : ::google::protobuf::Message(arena) { + RespondZoomInStartResponse* 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_.camera_server_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(arena, *from._impl_.camera_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondZoomInStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE RespondZoomInStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RespondZoomInStartResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_server_result_ = {}; +} +RespondZoomInStartResponse::~RespondZoomInStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondZoomInStartResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RespondZoomInStartResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_server_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RespondZoomInStartResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondZoomInStartResponse) + 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_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RespondZoomInStartResponse::_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<0, 1, 1, 0, 2> RespondZoomInStartResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(RespondZoomInStartResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_RespondZoomInStartResponse_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(RespondZoomInStartResponse, _impl_.camera_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + {PROTOBUF_FIELD_OFFSET(RespondZoomInStartResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::CameraServerResult>()}, + }}, {{ + }}, +}; + +::uint8_t* RespondZoomInStartResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondZoomInStartResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + 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.RespondZoomInStartResponse) + return target; +} + +::size_t RespondZoomInStartResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondZoomInStartResponse) + ::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.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RespondZoomInStartResponse::_class_data_ = { + RespondZoomInStartResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RespondZoomInStartResponse::GetClassData() const { + return &_class_data_; +} + +void RespondZoomInStartResponse::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.RespondZoomInStartResponse) + 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_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondZoomInStartResponse::CopyFrom(const RespondZoomInStartResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondZoomInStartResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RespondZoomInStartResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RespondZoomInStartResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RespondZoomInStartResponse::InternalSwap(RespondZoomInStartResponse* 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 RespondZoomInStartResponse::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]); +} +// =================================================================== + +class SubscribeZoomOutStartRequest::_Internal { + public: +}; + +SubscribeZoomOutStartRequest::SubscribeZoomOutStartRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeZoomOutStartRequest) +} +SubscribeZoomOutStartRequest::SubscribeZoomOutStartRequest( + ::google::protobuf::Arena* arena, + const SubscribeZoomOutStartRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeZoomOutStartRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeZoomOutStartRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeZoomOutStartRequest::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]); +} +// =================================================================== + +class ZoomOutStartResponse::_Internal { + public: +}; + +ZoomOutStartResponse::ZoomOutStartResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.ZoomOutStartResponse) +} +ZoomOutStartResponse::ZoomOutStartResponse( + ::google::protobuf::Arena* arena, const ZoomOutStartResponse& from) + : ZoomOutStartResponse(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ZoomOutStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomOutStartResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.reserved_ = {}; +} +ZoomOutStartResponse::~ZoomOutStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.ZoomOutStartResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomOutStartResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomOutStartResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.ZoomOutStartResponse) + 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_.reserved_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomOutStartResponse::_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<0, 1, 0, 0, 2> ZoomOutStartResponse::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ZoomOutStartResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 reserved = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ZoomOutStartResponse, _impl_.reserved_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_.reserved_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 reserved = 1; + {PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_.reserved_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ZoomOutStartResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.ZoomOutStartResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_reserved(), 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.ZoomOutStartResponse) + return target; +} + +::size_t ZoomOutStartResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.ZoomOutStartResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_reserved()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomOutStartResponse::_class_data_ = { + ZoomOutStartResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomOutStartResponse::GetClassData() const { + return &_class_data_; +} + +void ZoomOutStartResponse::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.ZoomOutStartResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_reserved() != 0) { + _this->_internal_set_reserved(from._internal_reserved()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomOutStartResponse::CopyFrom(const ZoomOutStartResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.ZoomOutStartResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomOutStartResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomOutStartResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomOutStartResponse::InternalSwap(ZoomOutStartResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.reserved_, other->_impl_.reserved_); +} + +::google::protobuf::Metadata ZoomOutStartResponse::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]); +} +// =================================================================== + +class RespondZoomOutStartRequest::_Internal { + public: +}; + +RespondZoomOutStartRequest::RespondZoomOutStartRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondZoomOutStartRequest) +} +RespondZoomOutStartRequest::RespondZoomOutStartRequest( + ::google::protobuf::Arena* arena, const RespondZoomOutStartRequest& from) + : RespondZoomOutStartRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE RespondZoomOutStartRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RespondZoomOutStartRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.zoom_out_start_feedback_ = {}; +} +RespondZoomOutStartRequest::~RespondZoomOutStartRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondZoomOutStartRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RespondZoomOutStartRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RespondZoomOutStartRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondZoomOutStartRequest) + 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_.zoom_out_start_feedback_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RespondZoomOutStartRequest::_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<0, 1, 0, 0, 2> RespondZoomOutStartRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_RespondZoomOutStartRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera_server.CameraFeedback zoom_out_start_feedback = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RespondZoomOutStartRequest, _impl_.zoom_out_start_feedback_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(RespondZoomOutStartRequest, _impl_.zoom_out_start_feedback_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera_server.CameraFeedback zoom_out_start_feedback = 1; + {PROTOBUF_FIELD_OFFSET(RespondZoomOutStartRequest, _impl_.zoom_out_start_feedback_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* RespondZoomOutStartRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondZoomOutStartRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback zoom_out_start_feedback = 1; + if (this->_internal_zoom_out_start_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_zoom_out_start_feedback(), 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.RespondZoomOutStartRequest) + return target; +} + +::size_t RespondZoomOutStartRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondZoomOutStartRequest) + ::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.CameraFeedback zoom_out_start_feedback = 1; + if (this->_internal_zoom_out_start_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_zoom_out_start_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RespondZoomOutStartRequest::_class_data_ = { + RespondZoomOutStartRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RespondZoomOutStartRequest::GetClassData() const { + return &_class_data_; +} + +void RespondZoomOutStartRequest::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.RespondZoomOutStartRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_zoom_out_start_feedback() != 0) { + _this->_internal_set_zoom_out_start_feedback(from._internal_zoom_out_start_feedback()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondZoomOutStartRequest::CopyFrom(const RespondZoomOutStartRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondZoomOutStartRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RespondZoomOutStartRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RespondZoomOutStartRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RespondZoomOutStartRequest::InternalSwap(RespondZoomOutStartRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.zoom_out_start_feedback_, other->_impl_.zoom_out_start_feedback_); +} + +::google::protobuf::Metadata RespondZoomOutStartRequest::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]); +} +// =================================================================== + +class RespondZoomOutStartResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondZoomOutStartResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondZoomOutStartResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomOutStartResponse::_Internal::camera_server_result(const RespondZoomOutStartResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondZoomOutStartResponse::RespondZoomOutStartResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondZoomOutStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE RespondZoomOutStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +RespondZoomOutStartResponse::RespondZoomOutStartResponse( + ::google::protobuf::Arena* arena, + const RespondZoomOutStartResponse& from) + : ::google::protobuf::Message(arena) { + RespondZoomOutStartResponse* 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_.camera_server_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(arena, *from._impl_.camera_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondZoomOutStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE RespondZoomOutStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RespondZoomOutStartResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_server_result_ = {}; +} +RespondZoomOutStartResponse::~RespondZoomOutStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondZoomOutStartResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RespondZoomOutStartResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_server_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RespondZoomOutStartResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondZoomOutStartResponse) + 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_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RespondZoomOutStartResponse::_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<0, 1, 1, 0, 2> RespondZoomOutStartResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(RespondZoomOutStartResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_RespondZoomOutStartResponse_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(RespondZoomOutStartResponse, _impl_.camera_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + {PROTOBUF_FIELD_OFFSET(RespondZoomOutStartResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::CameraServerResult>()}, + }}, {{ + }}, +}; + +::uint8_t* RespondZoomOutStartResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondZoomOutStartResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + 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.RespondZoomOutStartResponse) + return target; +} + +::size_t RespondZoomOutStartResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondZoomOutStartResponse) + ::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.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RespondZoomOutStartResponse::_class_data_ = { + RespondZoomOutStartResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RespondZoomOutStartResponse::GetClassData() const { + return &_class_data_; +} + +void RespondZoomOutStartResponse::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.RespondZoomOutStartResponse) + 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_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondZoomOutStartResponse::CopyFrom(const RespondZoomOutStartResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondZoomOutStartResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RespondZoomOutStartResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RespondZoomOutStartResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RespondZoomOutStartResponse::InternalSwap(RespondZoomOutStartResponse* 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 RespondZoomOutStartResponse::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]); +} +// =================================================================== + +class SubscribeZoomStopRequest::_Internal { + public: +}; + +SubscribeZoomStopRequest::SubscribeZoomStopRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeZoomStopRequest) +} +SubscribeZoomStopRequest::SubscribeZoomStopRequest( + ::google::protobuf::Arena* arena, + const SubscribeZoomStopRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeZoomStopRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeZoomStopRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeZoomStopRequest::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[54]); +} +// =================================================================== + +class ZoomStopResponse::_Internal { + public: +}; + +ZoomStopResponse::ZoomStopResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.ZoomStopResponse) +} +ZoomStopResponse::ZoomStopResponse( + ::google::protobuf::Arena* arena, const ZoomStopResponse& from) + : ZoomStopResponse(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ZoomStopResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomStopResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.reserved_ = {}; +} +ZoomStopResponse::~ZoomStopResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.ZoomStopResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomStopResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomStopResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.ZoomStopResponse) + 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_.reserved_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomStopResponse::_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<0, 1, 0, 0, 2> ZoomStopResponse::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ZoomStopResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 reserved = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ZoomStopResponse, _impl_.reserved_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_.reserved_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 reserved = 1; + {PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_.reserved_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ZoomStopResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.ZoomStopResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_reserved(), 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.ZoomStopResponse) + return target; +} + +::size_t ZoomStopResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.ZoomStopResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_reserved()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomStopResponse::_class_data_ = { + ZoomStopResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomStopResponse::GetClassData() const { + return &_class_data_; +} + +void ZoomStopResponse::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.ZoomStopResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_reserved() != 0) { + _this->_internal_set_reserved(from._internal_reserved()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomStopResponse::CopyFrom(const ZoomStopResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.ZoomStopResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomStopResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomStopResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomStopResponse::InternalSwap(ZoomStopResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.reserved_, other->_impl_.reserved_); +} + +::google::protobuf::Metadata ZoomStopResponse::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[55]); +} +// =================================================================== + +class RespondZoomStopRequest::_Internal { + public: +}; + +RespondZoomStopRequest::RespondZoomStopRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondZoomStopRequest) +} +RespondZoomStopRequest::RespondZoomStopRequest( + ::google::protobuf::Arena* arena, const RespondZoomStopRequest& from) + : RespondZoomStopRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE RespondZoomStopRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RespondZoomStopRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.zoom_stop_feedback_ = {}; +} +RespondZoomStopRequest::~RespondZoomStopRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondZoomStopRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RespondZoomStopRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RespondZoomStopRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondZoomStopRequest) + 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_.zoom_stop_feedback_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RespondZoomStopRequest::_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<0, 1, 0, 0, 2> RespondZoomStopRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_RespondZoomStopRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RespondFormatStorageRequest, _impl_.format_storage_feedback_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(RespondFormatStorageRequest, _impl_.format_storage_feedback_)}}, + // .mavsdk.rpc.camera_server.CameraFeedback zoom_stop_feedback = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RespondZoomStopRequest, _impl_.zoom_stop_feedback_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(RespondZoomStopRequest, _impl_.zoom_stop_feedback_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; - {PROTOBUF_FIELD_OFFSET(RespondFormatStorageRequest, _impl_.format_storage_feedback_), 0, 0, + // .mavsdk.rpc.camera_server.CameraFeedback zoom_stop_feedback = 1; + {PROTOBUF_FIELD_OFFSET(RespondZoomStopRequest, _impl_.zoom_stop_feedback_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, // no aux_entries @@ -8472,18 +11306,18 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> RespondFormatStorageRequest::_table_ = }}, }; -::uint8_t* RespondFormatStorageRequest::_InternalSerialize( +::uint8_t* RespondZoomStopRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondZoomStopRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; - if (this->_internal_format_storage_feedback() != 0) { + // .mavsdk.rpc.camera_server.CameraFeedback zoom_stop_feedback = 1; + if (this->_internal_zoom_stop_feedback() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_format_storage_feedback(), target); + 1, this->_internal_zoom_stop_feedback(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8491,106 +11325,106 @@ ::uint8_t* RespondFormatStorageRequest::_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.RespondFormatStorageRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondZoomStopRequest) return target; } -::size_t RespondFormatStorageRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) +::size_t RespondZoomStopRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondZoomStopRequest) ::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.CameraFeedback format_storage_feedback = 1; - if (this->_internal_format_storage_feedback() != 0) { + // .mavsdk.rpc.camera_server.CameraFeedback zoom_stop_feedback = 1; + if (this->_internal_zoom_stop_feedback() != 0) { total_size += 1 + - ::_pbi::WireFormatLite::EnumSize(this->_internal_format_storage_feedback()); + ::_pbi::WireFormatLite::EnumSize(this->_internal_zoom_stop_feedback()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData RespondFormatStorageRequest::_class_data_ = { - RespondFormatStorageRequest::MergeImpl, +const ::google::protobuf::Message::ClassData RespondZoomStopRequest::_class_data_ = { + RespondZoomStopRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* RespondFormatStorageRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* RespondZoomStopRequest::GetClassData() const { return &_class_data_; } -void RespondFormatStorageRequest::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.RespondFormatStorageRequest) +void RespondZoomStopRequest::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.RespondZoomStopRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_format_storage_feedback() != 0) { - _this->_internal_set_format_storage_feedback(from._internal_format_storage_feedback()); + if (from._internal_zoom_stop_feedback() != 0) { + _this->_internal_set_zoom_stop_feedback(from._internal_zoom_stop_feedback()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void RespondFormatStorageRequest::CopyFrom(const RespondFormatStorageRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) +void RespondZoomStopRequest::CopyFrom(const RespondZoomStopRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondZoomStopRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool RespondFormatStorageRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool RespondZoomStopRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* RespondFormatStorageRequest::AccessCachedSize() const { +::_pbi::CachedSize* RespondZoomStopRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void RespondFormatStorageRequest::InternalSwap(RespondFormatStorageRequest* PROTOBUF_RESTRICT other) { +void RespondZoomStopRequest::InternalSwap(RespondZoomStopRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.format_storage_feedback_, other->_impl_.format_storage_feedback_); + swap(_impl_.zoom_stop_feedback_, other->_impl_.zoom_stop_feedback_); } -::google::protobuf::Metadata RespondFormatStorageRequest::GetMetadata() const { +::google::protobuf::Metadata RespondZoomStopRequest::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[40]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[56]); } // =================================================================== -class RespondFormatStorageResponse::_Internal { +class RespondZoomStopResponse::_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(RespondFormatStorageResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondFormatStorageResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(RespondZoomStopResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondZoomStopResponse* msg); static void set_has_camera_server_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera_server::CameraServerResult& RespondFormatStorageResponse::_Internal::camera_server_result(const RespondFormatStorageResponse* msg) { +const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomStopResponse::_Internal::camera_server_result(const RespondZoomStopResponse* msg) { return *msg->_impl_.camera_server_result_; } -RespondFormatStorageResponse::RespondFormatStorageResponse(::google::protobuf::Arena* arena) +RespondZoomStopResponse::RespondZoomStopResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondZoomStopResponse) } -inline PROTOBUF_NDEBUG_INLINE RespondFormatStorageResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RespondZoomStopResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -RespondFormatStorageResponse::RespondFormatStorageResponse( +RespondZoomStopResponse::RespondZoomStopResponse( ::google::protobuf::Arena* arena, - const RespondFormatStorageResponse& from) + const RespondZoomStopResponse& from) : ::google::protobuf::Message(arena) { - RespondFormatStorageResponse* const _this = this; + RespondZoomStopResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -8600,30 +11434,30 @@ RespondFormatStorageResponse::RespondFormatStorageResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(arena, *from._impl_.camera_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondZoomStopResponse) } -inline PROTOBUF_NDEBUG_INLINE RespondFormatStorageResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RespondZoomStopResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void RespondFormatStorageResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondZoomStopResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_server_result_ = {}; } -RespondFormatStorageResponse::~RespondFormatStorageResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) +RespondZoomStopResponse::~RespondZoomStopResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondZoomStopResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void RespondFormatStorageResponse::SharedDtor() { +inline void RespondZoomStopResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_server_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void RespondFormatStorageResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) +PROTOBUF_NOINLINE void RespondZoomStopResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondZoomStopResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8638,7 +11472,7 @@ PROTOBUF_NOINLINE void RespondFormatStorageResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* RespondFormatStorageResponse::_InternalParse( +const char* RespondZoomStopResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8646,9 +11480,9 @@ const char* RespondFormatStorageResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RespondFormatStorageResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RespondZoomStopResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(RespondFormatStorageResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(RespondZoomStopResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8657,17 +11491,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RespondFormatStorageResponse::_table_ 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_RespondFormatStorageResponse_default_instance_._instance, + &_RespondZoomStopResponse_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(RespondFormatStorageResponse, _impl_.camera_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(RespondZoomStopResponse, _impl_.camera_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - {PROTOBUF_FIELD_OFFSET(RespondFormatStorageResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(RespondZoomStopResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::CameraServerResult>()}, @@ -8675,10 +11509,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RespondFormatStorageResponse::_table_ }}, }; -::uint8_t* RespondFormatStorageResponse::_InternalSerialize( +::uint8_t* RespondZoomStopResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondZoomStopResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -8695,12 +11529,12 @@ ::uint8_t* RespondFormatStorageResponse::_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.RespondFormatStorageResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondZoomStopResponse) return target; } -::size_t RespondFormatStorageResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) +::size_t RespondZoomStopResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondZoomStopResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -8717,18 +11551,18 @@ ::size_t RespondFormatStorageResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData RespondFormatStorageResponse::_class_data_ = { - RespondFormatStorageResponse::MergeImpl, +const ::google::protobuf::Message::ClassData RespondZoomStopResponse::_class_data_ = { + RespondZoomStopResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* RespondFormatStorageResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* RespondZoomStopResponse::GetClassData() const { return &_class_data_; } -void RespondFormatStorageResponse::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.RespondFormatStorageResponse) +void RespondZoomStopResponse::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.RespondZoomStopResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -8740,52 +11574,52 @@ void RespondFormatStorageResponse::MergeImpl(::google::protobuf::Message& to_msg _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void RespondFormatStorageResponse::CopyFrom(const RespondFormatStorageResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) +void RespondZoomStopResponse::CopyFrom(const RespondZoomStopResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondZoomStopResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool RespondFormatStorageResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool RespondZoomStopResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* RespondFormatStorageResponse::AccessCachedSize() const { +::_pbi::CachedSize* RespondZoomStopResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void RespondFormatStorageResponse::InternalSwap(RespondFormatStorageResponse* PROTOBUF_RESTRICT other) { +void RespondZoomStopResponse::InternalSwap(RespondZoomStopResponse* 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 RespondFormatStorageResponse::GetMetadata() const { +::google::protobuf::Metadata RespondZoomStopResponse::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[41]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[57]); } // =================================================================== -class SubscribeResetSettingsRequest::_Internal { +class SubscribeZoomRangeRequest::_Internal { public: }; -SubscribeResetSettingsRequest::SubscribeResetSettingsRequest(::google::protobuf::Arena* arena) +SubscribeZoomRangeRequest::SubscribeZoomRangeRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeZoomRangeRequest) } -SubscribeResetSettingsRequest::SubscribeResetSettingsRequest( +SubscribeZoomRangeRequest::SubscribeZoomRangeRequest( ::google::protobuf::Arena* arena, - const SubscribeResetSettingsRequest& from) + const SubscribeZoomRangeRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeResetSettingsRequest* const _this = this; + SubscribeZoomRangeRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeZoomRangeRequest) } @@ -8796,58 +11630,58 @@ SubscribeResetSettingsRequest::SubscribeResetSettingsRequest( -::google::protobuf::Metadata SubscribeResetSettingsRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeZoomRangeRequest::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[42]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[58]); } // =================================================================== -class ResetSettingsResponse::_Internal { +class ZoomRangeResponse::_Internal { public: }; -ResetSettingsResponse::ResetSettingsResponse(::google::protobuf::Arena* arena) +ZoomRangeResponse::ZoomRangeResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.ResetSettingsResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.ZoomRangeResponse) } -ResetSettingsResponse::ResetSettingsResponse( - ::google::protobuf::Arena* arena, const ResetSettingsResponse& from) - : ResetSettingsResponse(arena) { +ZoomRangeResponse::ZoomRangeResponse( + ::google::protobuf::Arena* arena, const ZoomRangeResponse& from) + : ZoomRangeResponse(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE ResetSettingsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ZoomRangeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { +inline void ZoomRangeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.reserved_ = {}; + _impl_.factor_ = {}; } -ResetSettingsResponse::~ResetSettingsResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.ResetSettingsResponse) +ZoomRangeResponse::~ZoomRangeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.ZoomRangeResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ResetSettingsResponse::SharedDtor() { +inline void ZoomRangeResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ResetSettingsResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.ResetSettingsResponse) +PROTOBUF_NOINLINE void ZoomRangeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.ZoomRangeResponse) 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_.reserved_ = 0; + _impl_.factor_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ResetSettingsResponse::_InternalParse( +const char* ZoomRangeResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8855,7 +11689,7 @@ const char* ResetSettingsResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ResetSettingsResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ZoomRangeResponse::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -8866,36 +11700,41 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ResetSettingsResponse::_table_ = { 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_ResetSettingsResponse_default_instance_._instance, + &_ZoomRangeResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // int32 reserved = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ResetSettingsResponse, _impl_.reserved_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_.reserved_)}}, + // float factor = 1; + {::_pbi::TcParser::FastF32S1, + {13, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_.factor_)}}, }}, {{ 65535, 65535 }}, {{ - // int32 reserved = 1; - {PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_.reserved_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float factor = 1; + {PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_.factor_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, // no aux_entries {{ }}, }; -::uint8_t* ResetSettingsResponse::_InternalSerialize( +::uint8_t* ZoomRangeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.ZoomRangeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // int32 reserved = 1; - if (this->_internal_reserved() != 0) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteInt32ToArrayWithField<1>( - stream, this->_internal_reserved(), target); + // float factor = 1; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_factor = this->_internal_factor(); + ::uint32_t raw_factor; + memcpy(&raw_factor, &tmp_factor, sizeof(tmp_factor)); + if (raw_factor != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 1, this->_internal_factor(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8903,121 +11742,130 @@ ::uint8_t* ResetSettingsResponse::_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.ResetSettingsResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.ZoomRangeResponse) return target; } -::size_t ResetSettingsResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.ResetSettingsResponse) +::size_t ZoomRangeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.ZoomRangeResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 reserved = 1; - if (this->_internal_reserved() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_reserved()); + // float factor = 1; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_factor = this->_internal_factor(); + ::uint32_t raw_factor; + memcpy(&raw_factor, &tmp_factor, sizeof(tmp_factor)); + if (raw_factor != 0) { + total_size += 5; } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ResetSettingsResponse::_class_data_ = { - ResetSettingsResponse::MergeImpl, +const ::google::protobuf::Message::ClassData ZoomRangeResponse::_class_data_ = { + ZoomRangeResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ResetSettingsResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* ZoomRangeResponse::GetClassData() const { return &_class_data_; } -void ResetSettingsResponse::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.ResetSettingsResponse) +void ZoomRangeResponse::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.ZoomRangeResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_reserved() != 0) { - _this->_internal_set_reserved(from._internal_reserved()); + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_factor = from._internal_factor(); + ::uint32_t raw_factor; + memcpy(&raw_factor, &tmp_factor, sizeof(tmp_factor)); + if (raw_factor != 0) { + _this->_internal_set_factor(from._internal_factor()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ResetSettingsResponse::CopyFrom(const ResetSettingsResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.ResetSettingsResponse) +void ZoomRangeResponse::CopyFrom(const ZoomRangeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.ZoomRangeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ResetSettingsResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool ZoomRangeResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ResetSettingsResponse::AccessCachedSize() const { +::_pbi::CachedSize* ZoomRangeResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* PROTOBUF_RESTRICT other) { +void ZoomRangeResponse::InternalSwap(ZoomRangeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.reserved_, other->_impl_.reserved_); + swap(_impl_.factor_, other->_impl_.factor_); } -::google::protobuf::Metadata ResetSettingsResponse::GetMetadata() const { +::google::protobuf::Metadata ZoomRangeResponse::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[43]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[59]); } // =================================================================== -class RespondResetSettingsRequest::_Internal { +class RespondZoomRangeRequest::_Internal { public: }; -RespondResetSettingsRequest::RespondResetSettingsRequest(::google::protobuf::Arena* arena) +RespondZoomRangeRequest::RespondZoomRangeRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondZoomRangeRequest) } -RespondResetSettingsRequest::RespondResetSettingsRequest( - ::google::protobuf::Arena* arena, const RespondResetSettingsRequest& from) - : RespondResetSettingsRequest(arena) { +RespondZoomRangeRequest::RespondZoomRangeRequest( + ::google::protobuf::Arena* arena, const RespondZoomRangeRequest& from) + : RespondZoomRangeRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE RespondResetSettingsRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RespondZoomRangeRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void RespondResetSettingsRequest::SharedCtor(::_pb::Arena* arena) { +inline void RespondZoomRangeRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.reset_settings_feedback_ = {}; + _impl_.zoom_range_feedback_ = {}; } -RespondResetSettingsRequest::~RespondResetSettingsRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondResetSettingsRequest) +RespondZoomRangeRequest::~RespondZoomRangeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondZoomRangeRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void RespondResetSettingsRequest::SharedDtor() { +inline void RespondZoomRangeRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void RespondResetSettingsRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) +PROTOBUF_NOINLINE void RespondZoomRangeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondZoomRangeRequest) 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_.reset_settings_feedback_ = 0; + _impl_.zoom_range_feedback_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* RespondResetSettingsRequest::_InternalParse( +const char* RespondZoomRangeRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9025,7 +11873,7 @@ const char* RespondResetSettingsRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> RespondResetSettingsRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> RespondZoomRangeRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -9036,17 +11884,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> RespondResetSettingsRequest::_table_ = 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_RespondResetSettingsRequest_default_instance_._instance, + &_RespondZoomRangeRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RespondResetSettingsRequest, _impl_.reset_settings_feedback_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(RespondResetSettingsRequest, _impl_.reset_settings_feedback_)}}, + // .mavsdk.rpc.camera_server.CameraFeedback zoom_range_feedback = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RespondZoomRangeRequest, _impl_.zoom_range_feedback_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(RespondZoomRangeRequest, _impl_.zoom_range_feedback_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; - {PROTOBUF_FIELD_OFFSET(RespondResetSettingsRequest, _impl_.reset_settings_feedback_), 0, 0, + // .mavsdk.rpc.camera_server.CameraFeedback zoom_range_feedback = 1; + {PROTOBUF_FIELD_OFFSET(RespondZoomRangeRequest, _impl_.zoom_range_feedback_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, // no aux_entries @@ -9054,18 +11902,18 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> RespondResetSettingsRequest::_table_ = }}, }; -::uint8_t* RespondResetSettingsRequest::_InternalSerialize( +::uint8_t* RespondZoomRangeRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondZoomRangeRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; - if (this->_internal_reset_settings_feedback() != 0) { + // .mavsdk.rpc.camera_server.CameraFeedback zoom_range_feedback = 1; + if (this->_internal_zoom_range_feedback() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_reset_settings_feedback(), target); + 1, this->_internal_zoom_range_feedback(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -9073,106 +11921,106 @@ ::uint8_t* RespondResetSettingsRequest::_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.RespondResetSettingsRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondZoomRangeRequest) return target; } -::size_t RespondResetSettingsRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) +::size_t RespondZoomRangeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondZoomRangeRequest) ::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.CameraFeedback reset_settings_feedback = 1; - if (this->_internal_reset_settings_feedback() != 0) { + // .mavsdk.rpc.camera_server.CameraFeedback zoom_range_feedback = 1; + if (this->_internal_zoom_range_feedback() != 0) { total_size += 1 + - ::_pbi::WireFormatLite::EnumSize(this->_internal_reset_settings_feedback()); + ::_pbi::WireFormatLite::EnumSize(this->_internal_zoom_range_feedback()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData RespondResetSettingsRequest::_class_data_ = { - RespondResetSettingsRequest::MergeImpl, +const ::google::protobuf::Message::ClassData RespondZoomRangeRequest::_class_data_ = { + RespondZoomRangeRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* RespondResetSettingsRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* RespondZoomRangeRequest::GetClassData() const { return &_class_data_; } -void RespondResetSettingsRequest::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.RespondResetSettingsRequest) +void RespondZoomRangeRequest::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.RespondZoomRangeRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_reset_settings_feedback() != 0) { - _this->_internal_set_reset_settings_feedback(from._internal_reset_settings_feedback()); + if (from._internal_zoom_range_feedback() != 0) { + _this->_internal_set_zoom_range_feedback(from._internal_zoom_range_feedback()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void RespondResetSettingsRequest::CopyFrom(const RespondResetSettingsRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) +void RespondZoomRangeRequest::CopyFrom(const RespondZoomRangeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondZoomRangeRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool RespondResetSettingsRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool RespondZoomRangeRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* RespondResetSettingsRequest::AccessCachedSize() const { +::_pbi::CachedSize* RespondZoomRangeRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void RespondResetSettingsRequest::InternalSwap(RespondResetSettingsRequest* PROTOBUF_RESTRICT other) { +void RespondZoomRangeRequest::InternalSwap(RespondZoomRangeRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.reset_settings_feedback_, other->_impl_.reset_settings_feedback_); + swap(_impl_.zoom_range_feedback_, other->_impl_.zoom_range_feedback_); } -::google::protobuf::Metadata RespondResetSettingsRequest::GetMetadata() const { +::google::protobuf::Metadata RespondZoomRangeRequest::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[44]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[60]); } // =================================================================== -class RespondResetSettingsResponse::_Internal { +class RespondZoomRangeResponse::_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(RespondResetSettingsResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondResetSettingsResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(RespondZoomRangeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondZoomRangeResponse* msg); static void set_has_camera_server_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera_server::CameraServerResult& RespondResetSettingsResponse::_Internal::camera_server_result(const RespondResetSettingsResponse* msg) { +const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomRangeResponse::_Internal::camera_server_result(const RespondZoomRangeResponse* msg) { return *msg->_impl_.camera_server_result_; } -RespondResetSettingsResponse::RespondResetSettingsResponse(::google::protobuf::Arena* arena) +RespondZoomRangeResponse::RespondZoomRangeResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondZoomRangeResponse) } -inline PROTOBUF_NDEBUG_INLINE RespondResetSettingsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RespondZoomRangeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -RespondResetSettingsResponse::RespondResetSettingsResponse( +RespondZoomRangeResponse::RespondZoomRangeResponse( ::google::protobuf::Arena* arena, - const RespondResetSettingsResponse& from) + const RespondZoomRangeResponse& from) : ::google::protobuf::Message(arena) { - RespondResetSettingsResponse* const _this = this; + RespondZoomRangeResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -9182,30 +12030,30 @@ RespondResetSettingsResponse::RespondResetSettingsResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(arena, *from._impl_.camera_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondZoomRangeResponse) } -inline PROTOBUF_NDEBUG_INLINE RespondResetSettingsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RespondZoomRangeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void RespondResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondZoomRangeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_server_result_ = {}; } -RespondResetSettingsResponse::~RespondResetSettingsResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) +RespondZoomRangeResponse::~RespondZoomRangeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondZoomRangeResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void RespondResetSettingsResponse::SharedDtor() { +inline void RespondZoomRangeResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_server_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void RespondResetSettingsResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) +PROTOBUF_NOINLINE void RespondZoomRangeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondZoomRangeResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9220,7 +12068,7 @@ PROTOBUF_NOINLINE void RespondResetSettingsResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* RespondResetSettingsResponse::_InternalParse( +const char* RespondZoomRangeResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9228,9 +12076,9 @@ const char* RespondResetSettingsResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RespondResetSettingsResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RespondZoomRangeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(RespondResetSettingsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(RespondZoomRangeResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9239,17 +12087,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RespondResetSettingsResponse::_table_ 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_RespondResetSettingsResponse_default_instance_._instance, + &_RespondZoomRangeResponse_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(RespondResetSettingsResponse, _impl_.camera_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(RespondZoomRangeResponse, _impl_.camera_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - {PROTOBUF_FIELD_OFFSET(RespondResetSettingsResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(RespondZoomRangeResponse, _impl_.camera_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera_server::CameraServerResult>()}, @@ -9257,10 +12105,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RespondResetSettingsResponse::_table_ }}, }; -::uint8_t* RespondResetSettingsResponse::_InternalSerialize( +::uint8_t* RespondZoomRangeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondZoomRangeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -9277,12 +12125,12 @@ ::uint8_t* RespondResetSettingsResponse::_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.RespondResetSettingsResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondZoomRangeResponse) return target; } -::size_t RespondResetSettingsResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) +::size_t RespondZoomRangeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondZoomRangeResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -9299,18 +12147,18 @@ ::size_t RespondResetSettingsResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData RespondResetSettingsResponse::_class_data_ = { - RespondResetSettingsResponse::MergeImpl, +const ::google::protobuf::Message::ClassData RespondZoomRangeResponse::_class_data_ = { + RespondZoomRangeResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* RespondResetSettingsResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* RespondZoomRangeResponse::GetClassData() const { return &_class_data_; } -void RespondResetSettingsResponse::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.RespondResetSettingsResponse) +void RespondZoomRangeResponse::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.RespondZoomRangeResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -9322,31 +12170,31 @@ void RespondResetSettingsResponse::MergeImpl(::google::protobuf::Message& to_msg _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void RespondResetSettingsResponse::CopyFrom(const RespondResetSettingsResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) +void RespondZoomRangeResponse::CopyFrom(const RespondZoomRangeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondZoomRangeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool RespondResetSettingsResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool RespondZoomRangeResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* RespondResetSettingsResponse::AccessCachedSize() const { +::_pbi::CachedSize* RespondZoomRangeResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void RespondResetSettingsResponse::InternalSwap(RespondResetSettingsResponse* PROTOBUF_RESTRICT other) { +void RespondZoomRangeResponse::InternalSwap(RespondZoomRangeResponse* 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 RespondResetSettingsResponse::GetMetadata() const { +::google::protobuf::Metadata RespondZoomRangeResponse::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[45]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[61]); } // =================================================================== @@ -9846,7 +12694,7 @@ void Information::InternalSwap(Information* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Information::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[46]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[62]); } // =================================================================== @@ -10061,7 +12909,7 @@ void VideoStreaming::InternalSwap(VideoStreaming* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata VideoStreaming::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]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[63]); } // =================================================================== @@ -10365,7 +13213,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[64]); } // =================================================================== @@ -10669,7 +13517,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[65]); } // =================================================================== @@ -11042,7 +13890,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[66]); } // =================================================================== @@ -11258,7 +14106,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[67]); } // =================================================================== @@ -11664,7 +14512,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[68]); } // =================================================================== @@ -12000,7 +14848,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[69]); } // @@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..c2ccb31a2f 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 @@ -148,6 +148,30 @@ extern RespondTakePhotoRequestDefaultTypeInternal _RespondTakePhotoRequest_defau class RespondTakePhotoResponse; struct RespondTakePhotoResponseDefaultTypeInternal; extern RespondTakePhotoResponseDefaultTypeInternal _RespondTakePhotoResponse_default_instance_; +class RespondZoomInStartRequest; +struct RespondZoomInStartRequestDefaultTypeInternal; +extern RespondZoomInStartRequestDefaultTypeInternal _RespondZoomInStartRequest_default_instance_; +class RespondZoomInStartResponse; +struct RespondZoomInStartResponseDefaultTypeInternal; +extern RespondZoomInStartResponseDefaultTypeInternal _RespondZoomInStartResponse_default_instance_; +class RespondZoomOutStartRequest; +struct RespondZoomOutStartRequestDefaultTypeInternal; +extern RespondZoomOutStartRequestDefaultTypeInternal _RespondZoomOutStartRequest_default_instance_; +class RespondZoomOutStartResponse; +struct RespondZoomOutStartResponseDefaultTypeInternal; +extern RespondZoomOutStartResponseDefaultTypeInternal _RespondZoomOutStartResponse_default_instance_; +class RespondZoomRangeRequest; +struct RespondZoomRangeRequestDefaultTypeInternal; +extern RespondZoomRangeRequestDefaultTypeInternal _RespondZoomRangeRequest_default_instance_; +class RespondZoomRangeResponse; +struct RespondZoomRangeResponseDefaultTypeInternal; +extern RespondZoomRangeResponseDefaultTypeInternal _RespondZoomRangeResponse_default_instance_; +class RespondZoomStopRequest; +struct RespondZoomStopRequestDefaultTypeInternal; +extern RespondZoomStopRequestDefaultTypeInternal _RespondZoomStopRequest_default_instance_; +class RespondZoomStopResponse; +struct RespondZoomStopResponseDefaultTypeInternal; +extern RespondZoomStopResponseDefaultTypeInternal _RespondZoomStopResponse_default_instance_; class SetInProgressRequest; struct SetInProgressRequestDefaultTypeInternal; extern SetInProgressRequestDefaultTypeInternal _SetInProgressRequest_default_instance_; @@ -217,12 +241,36 @@ extern SubscribeStorageInformationRequestDefaultTypeInternal _SubscribeStorageIn class SubscribeTakePhotoRequest; struct SubscribeTakePhotoRequestDefaultTypeInternal; extern SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_default_instance_; +class SubscribeZoomInStartRequest; +struct SubscribeZoomInStartRequestDefaultTypeInternal; +extern SubscribeZoomInStartRequestDefaultTypeInternal _SubscribeZoomInStartRequest_default_instance_; +class SubscribeZoomOutStartRequest; +struct SubscribeZoomOutStartRequestDefaultTypeInternal; +extern SubscribeZoomOutStartRequestDefaultTypeInternal _SubscribeZoomOutStartRequest_default_instance_; +class SubscribeZoomRangeRequest; +struct SubscribeZoomRangeRequestDefaultTypeInternal; +extern SubscribeZoomRangeRequestDefaultTypeInternal _SubscribeZoomRangeRequest_default_instance_; +class SubscribeZoomStopRequest; +struct SubscribeZoomStopRequestDefaultTypeInternal; +extern SubscribeZoomStopRequestDefaultTypeInternal _SubscribeZoomStopRequest_default_instance_; class TakePhotoResponse; struct TakePhotoResponseDefaultTypeInternal; extern TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; class VideoStreaming; struct VideoStreamingDefaultTypeInternal; extern VideoStreamingDefaultTypeInternal _VideoStreaming_default_instance_; +class ZoomInStartResponse; +struct ZoomInStartResponseDefaultTypeInternal; +extern ZoomInStartResponseDefaultTypeInternal _ZoomInStartResponse_default_instance_; +class ZoomOutStartResponse; +struct ZoomOutStartResponseDefaultTypeInternal; +extern ZoomOutStartResponseDefaultTypeInternal _ZoomOutStartResponse_default_instance_; +class ZoomRangeResponse; +struct ZoomRangeResponseDefaultTypeInternal; +extern ZoomRangeResponseDefaultTypeInternal _ZoomRangeResponse_default_instance_; +class ZoomStopResponse; +struct ZoomStopResponseDefaultTypeInternal; +extern ZoomStopResponseDefaultTypeInternal _ZoomStopResponse_default_instance_; } // namespace camera_server } // namespace rpc } // namespace mavsdk @@ -483,26 +531,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 ZoomStopResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ZoomStopResponse) */ { public: - inline VideoStreaming() : VideoStreaming(nullptr) {} - ~VideoStreaming() override; + inline ZoomStopResponse() : ZoomStopResponse(nullptr) {} + ~ZoomStopResponse() override; template - explicit PROTOBUF_CONSTEXPR VideoStreaming(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ZoomStopResponse(::google::protobuf::internal::ConstantInitialized); - inline VideoStreaming(const VideoStreaming& from) - : VideoStreaming(nullptr, from) {} - VideoStreaming(VideoStreaming&& from) noexcept - : VideoStreaming() { + inline ZoomStopResponse(const ZoomStopResponse& from) + : ZoomStopResponse(nullptr, from) {} + ZoomStopResponse(ZoomStopResponse&& from) noexcept + : ZoomStopResponse() { *this = ::std::move(from); } - inline VideoStreaming& operator=(const VideoStreaming& from) { + inline ZoomStopResponse& operator=(const ZoomStopResponse& from) { CopyFrom(from); return *this; } - inline VideoStreaming& operator=(VideoStreaming&& from) noexcept { + inline ZoomStopResponse& operator=(ZoomStopResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -534,20 +582,20 @@ class VideoStreaming final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const VideoStreaming& default_instance() { + static const ZoomStopResponse& default_instance() { return *internal_default_instance(); } - static inline const VideoStreaming* internal_default_instance() { - return reinterpret_cast( - &_VideoStreaming_default_instance_); + static inline const ZoomStopResponse* internal_default_instance() { + return reinterpret_cast( + &_ZoomStopResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 47; + 55; - friend void swap(VideoStreaming& a, VideoStreaming& b) { + friend void swap(ZoomStopResponse& a, ZoomStopResponse& b) { a.Swap(&b); } - inline void Swap(VideoStreaming* other) { + inline void Swap(ZoomStopResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -560,7 +608,7 @@ class VideoStreaming final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(VideoStreaming* other) { + void UnsafeArenaSwap(ZoomStopResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -568,14 +616,14 @@ class VideoStreaming final : // implements Message ---------------------------------------------- - VideoStreaming* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ZoomStopResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const VideoStreaming& from); + void CopyFrom(const ZoomStopResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const VideoStreaming& from) { - VideoStreaming::MergeImpl(*this, from); + void MergeFrom( const ZoomStopResponse& from) { + ZoomStopResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -593,16 +641,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(ZoomStopResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.VideoStreaming"; + return "mavsdk.rpc.camera_server.ZoomStopResponse"; } protected: - explicit VideoStreaming(::google::protobuf::Arena* arena); - VideoStreaming(::google::protobuf::Arena* arena, const VideoStreaming& from); + explicit ZoomStopResponse(::google::protobuf::Arena* arena); + ZoomStopResponse(::google::protobuf::Arena* arena, const ZoomStopResponse& from); public: static const ClassData _class_data_; @@ -615,43 +663,26 @@ class VideoStreaming final : // accessors ------------------------------------------------------- enum : int { - kRtspUriFieldNumber = 2, - kHasRtspServerFieldNumber = 1, + kReservedFieldNumber = 1, }; - // string rtsp_uri = 2; - void clear_rtsp_uri() ; - const std::string& rtsp_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); - - private: - const std::string& _internal_rtsp_uri() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_rtsp_uri( - const std::string& value); - std::string* _internal_mutable_rtsp_uri(); - - public: - // bool has_rtsp_server = 1; - void clear_has_rtsp_server() ; - bool has_rtsp_server() const; - void set_has_rtsp_server(bool value); + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); private: - bool _internal_has_rtsp_server() const; - void _internal_set_has_rtsp_server(bool value); + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.VideoStreaming) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ZoomStopResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, - 56, 2> + 0, 1, 0, + 0, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -667,8 +698,7 @@ 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_; + ::int32_t reserved_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -676,26 +706,26 @@ class VideoStreaming final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class TakePhotoResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.TakePhotoResponse) */ { +class ZoomRangeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ZoomRangeResponse) */ { public: - inline TakePhotoResponse() : TakePhotoResponse(nullptr) {} - ~TakePhotoResponse() override; + inline ZoomRangeResponse() : ZoomRangeResponse(nullptr) {} + ~ZoomRangeResponse() override; template - explicit PROTOBUF_CONSTEXPR TakePhotoResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ZoomRangeResponse(::google::protobuf::internal::ConstantInitialized); - inline TakePhotoResponse(const TakePhotoResponse& from) - : TakePhotoResponse(nullptr, from) {} - TakePhotoResponse(TakePhotoResponse&& from) noexcept - : TakePhotoResponse() { + inline ZoomRangeResponse(const ZoomRangeResponse& from) + : ZoomRangeResponse(nullptr, from) {} + ZoomRangeResponse(ZoomRangeResponse&& from) noexcept + : ZoomRangeResponse() { *this = ::std::move(from); } - inline TakePhotoResponse& operator=(const TakePhotoResponse& from) { + inline ZoomRangeResponse& operator=(const ZoomRangeResponse& from) { CopyFrom(from); return *this; } - inline TakePhotoResponse& operator=(TakePhotoResponse&& from) noexcept { + inline ZoomRangeResponse& operator=(ZoomRangeResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -727,20 +757,20 @@ class TakePhotoResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const TakePhotoResponse& default_instance() { + static const ZoomRangeResponse& default_instance() { return *internal_default_instance(); } - static inline const TakePhotoResponse* internal_default_instance() { - return reinterpret_cast( - &_TakePhotoResponse_default_instance_); + static inline const ZoomRangeResponse* internal_default_instance() { + return reinterpret_cast( + &_ZoomRangeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 7; + 59; - friend void swap(TakePhotoResponse& a, TakePhotoResponse& b) { + friend void swap(ZoomRangeResponse& a, ZoomRangeResponse& b) { a.Swap(&b); } - inline void Swap(TakePhotoResponse* other) { + inline void Swap(ZoomRangeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -753,7 +783,7 @@ class TakePhotoResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(TakePhotoResponse* other) { + void UnsafeArenaSwap(ZoomRangeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -761,14 +791,14 @@ class TakePhotoResponse final : // implements Message ---------------------------------------------- - TakePhotoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ZoomRangeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const TakePhotoResponse& from); + void CopyFrom(const ZoomRangeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const TakePhotoResponse& from) { - TakePhotoResponse::MergeImpl(*this, from); + void MergeFrom( const ZoomRangeResponse& from) { + ZoomRangeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -786,16 +816,16 @@ class TakePhotoResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(TakePhotoResponse* other); + void InternalSwap(ZoomRangeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.TakePhotoResponse"; + return "mavsdk.rpc.camera_server.ZoomRangeResponse"; } protected: - explicit TakePhotoResponse(::google::protobuf::Arena* arena); - TakePhotoResponse(::google::protobuf::Arena* arena, const TakePhotoResponse& from); + explicit ZoomRangeResponse(::google::protobuf::Arena* arena); + ZoomRangeResponse(::google::protobuf::Arena* arena, const ZoomRangeResponse& from); public: static const ClassData _class_data_; @@ -808,19 +838,19 @@ class TakePhotoResponse final : // accessors ------------------------------------------------------- enum : int { - kIndexFieldNumber = 1, + kFactorFieldNumber = 1, }; - // int32 index = 1; - void clear_index() ; - ::int32_t index() const; - void set_index(::int32_t value); + // float factor = 1; + void clear_factor() ; + float factor() const; + void set_factor(float value); private: - ::int32_t _internal_index() const; - void _internal_set_index(::int32_t value); + float _internal_factor() const; + void _internal_set_factor(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.TakePhotoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ZoomRangeResponse) private: class _Internal; @@ -843,7 +873,7 @@ class TakePhotoResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t index_; + float factor_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -851,25 +881,26 @@ class TakePhotoResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeTakePhotoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) */ { +class ZoomOutStartResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ZoomOutStartResponse) */ { public: - inline SubscribeTakePhotoRequest() : SubscribeTakePhotoRequest(nullptr) {} + inline ZoomOutStartResponse() : ZoomOutStartResponse(nullptr) {} + ~ZoomOutStartResponse() override; template - explicit PROTOBUF_CONSTEXPR SubscribeTakePhotoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ZoomOutStartResponse(::google::protobuf::internal::ConstantInitialized); - inline SubscribeTakePhotoRequest(const SubscribeTakePhotoRequest& from) - : SubscribeTakePhotoRequest(nullptr, from) {} - SubscribeTakePhotoRequest(SubscribeTakePhotoRequest&& from) noexcept - : SubscribeTakePhotoRequest() { + inline ZoomOutStartResponse(const ZoomOutStartResponse& from) + : ZoomOutStartResponse(nullptr, from) {} + ZoomOutStartResponse(ZoomOutStartResponse&& from) noexcept + : ZoomOutStartResponse() { *this = ::std::move(from); } - inline SubscribeTakePhotoRequest& operator=(const SubscribeTakePhotoRequest& from) { + inline ZoomOutStartResponse& operator=(const ZoomOutStartResponse& from) { CopyFrom(from); return *this; } - inline SubscribeTakePhotoRequest& operator=(SubscribeTakePhotoRequest&& from) noexcept { + inline ZoomOutStartResponse& operator=(ZoomOutStartResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -901,20 +932,20 @@ class SubscribeTakePhotoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeTakePhotoRequest& default_instance() { + static const ZoomOutStartResponse& default_instance() { return *internal_default_instance(); } - static inline const SubscribeTakePhotoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeTakePhotoRequest_default_instance_); + static inline const ZoomOutStartResponse* internal_default_instance() { + return reinterpret_cast( + &_ZoomOutStartResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 6; + 51; - friend void swap(SubscribeTakePhotoRequest& a, SubscribeTakePhotoRequest& b) { + friend void swap(ZoomOutStartResponse& a, ZoomOutStartResponse& b) { a.Swap(&b); } - inline void Swap(SubscribeTakePhotoRequest* other) { + inline void Swap(ZoomOutStartResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -927,7 +958,7 @@ class SubscribeTakePhotoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeTakePhotoRequest* other) { + void UnsafeArenaSwap(ZoomOutStartResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -935,39 +966,74 @@ class SubscribeTakePhotoRequest final : // implements Message ---------------------------------------------- - SubscribeTakePhotoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeTakePhotoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + ZoomOutStartResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeTakePhotoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ZoomOutStartResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ZoomOutStartResponse& from) { + ZoomOutStartResponse::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(ZoomOutStartResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeTakePhotoRequest"; + return "mavsdk.rpc.camera_server.ZoomOutStartResponse"; } protected: - explicit SubscribeTakePhotoRequest(::google::protobuf::Arena* arena); - SubscribeTakePhotoRequest(::google::protobuf::Arena* arena, const SubscribeTakePhotoRequest& from); + explicit ZoomOutStartResponse(::google::protobuf::Arena* arena); + ZoomOutStartResponse(::google::protobuf::Arena* arena, const ZoomOutStartResponse& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + enum : int { + kReservedFieldNumber = 1, + }; + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); + + private: + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ZoomOutStartResponse) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -982,30 +1048,34 @@ class SubscribeTakePhotoRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t reserved_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStorageInformationRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) */ { +class ZoomInStartResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ZoomInStartResponse) */ { public: - inline SubscribeStorageInformationRequest() : SubscribeStorageInformationRequest(nullptr) {} + inline ZoomInStartResponse() : ZoomInStartResponse(nullptr) {} + ~ZoomInStartResponse() override; template - explicit PROTOBUF_CONSTEXPR SubscribeStorageInformationRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ZoomInStartResponse(::google::protobuf::internal::ConstantInitialized); - inline SubscribeStorageInformationRequest(const SubscribeStorageInformationRequest& from) - : SubscribeStorageInformationRequest(nullptr, from) {} - SubscribeStorageInformationRequest(SubscribeStorageInformationRequest&& from) noexcept - : SubscribeStorageInformationRequest() { + inline ZoomInStartResponse(const ZoomInStartResponse& from) + : ZoomInStartResponse(nullptr, from) {} + ZoomInStartResponse(ZoomInStartResponse&& from) noexcept + : ZoomInStartResponse() { *this = ::std::move(from); } - inline SubscribeStorageInformationRequest& operator=(const SubscribeStorageInformationRequest& from) { + inline ZoomInStartResponse& operator=(const ZoomInStartResponse& from) { CopyFrom(from); return *this; } - inline SubscribeStorageInformationRequest& operator=(SubscribeStorageInformationRequest&& from) noexcept { + inline ZoomInStartResponse& operator=(ZoomInStartResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1037,20 +1107,20 @@ class SubscribeStorageInformationRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStorageInformationRequest& default_instance() { + static const ZoomInStartResponse& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStorageInformationRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStorageInformationRequest_default_instance_); + static inline const ZoomInStartResponse* internal_default_instance() { + return reinterpret_cast( + &_ZoomInStartResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 30; + 47; - friend void swap(SubscribeStorageInformationRequest& a, SubscribeStorageInformationRequest& b) { + friend void swap(ZoomInStartResponse& a, ZoomInStartResponse& b) { a.Swap(&b); } - inline void Swap(SubscribeStorageInformationRequest* other) { + inline void Swap(ZoomInStartResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1063,7 +1133,7 @@ class SubscribeStorageInformationRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStorageInformationRequest* other) { + void UnsafeArenaSwap(ZoomInStartResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1071,39 +1141,74 @@ class SubscribeStorageInformationRequest final : // implements Message ---------------------------------------------- - SubscribeStorageInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStorageInformationRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + ZoomInStartResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStorageInformationRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ZoomInStartResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ZoomInStartResponse& from) { + ZoomInStartResponse::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(ZoomInStartResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStorageInformationRequest"; + return "mavsdk.rpc.camera_server.ZoomInStartResponse"; } protected: - explicit SubscribeStorageInformationRequest(::google::protobuf::Arena* arena); - SubscribeStorageInformationRequest(::google::protobuf::Arena* arena, const SubscribeStorageInformationRequest& from); + explicit ZoomInStartResponse(::google::protobuf::Arena* arena); + ZoomInStartResponse(::google::protobuf::Arena* arena, const ZoomInStartResponse& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) + enum : int { + kReservedFieldNumber = 1, + }; + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); + + private: + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ZoomInStartResponse) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -1118,30 +1223,34 @@ class SubscribeStorageInformationRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t reserved_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStopVideoStreamingRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) */ { +class VideoStreaming final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.VideoStreaming) */ { public: - inline SubscribeStopVideoStreamingRequest() : SubscribeStopVideoStreamingRequest(nullptr) {} - template - explicit PROTOBUF_CONSTEXPR SubscribeStopVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); + inline VideoStreaming() : VideoStreaming(nullptr) {} + ~VideoStreaming() override; + template + explicit PROTOBUF_CONSTEXPR VideoStreaming(::google::protobuf::internal::ConstantInitialized); - inline SubscribeStopVideoStreamingRequest(const SubscribeStopVideoStreamingRequest& from) - : SubscribeStopVideoStreamingRequest(nullptr, from) {} - SubscribeStopVideoStreamingRequest(SubscribeStopVideoStreamingRequest&& from) noexcept - : SubscribeStopVideoStreamingRequest() { + inline VideoStreaming(const VideoStreaming& from) + : VideoStreaming(nullptr, from) {} + VideoStreaming(VideoStreaming&& from) noexcept + : VideoStreaming() { *this = ::std::move(from); } - inline SubscribeStopVideoStreamingRequest& operator=(const SubscribeStopVideoStreamingRequest& from) { + inline VideoStreaming& operator=(const VideoStreaming& from) { CopyFrom(from); return *this; } - inline SubscribeStopVideoStreamingRequest& operator=(SubscribeStopVideoStreamingRequest&& from) noexcept { + inline VideoStreaming& operator=(VideoStreaming&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1173,20 +1282,20 @@ class SubscribeStopVideoStreamingRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStopVideoStreamingRequest& default_instance() { + static const VideoStreaming& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStopVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStopVideoStreamingRequest_default_instance_); + static inline const VideoStreaming* internal_default_instance() { + return reinterpret_cast( + &_VideoStreaming_default_instance_); } static constexpr int kIndexInFileMessages = - 22; + 63; - friend void swap(SubscribeStopVideoStreamingRequest& a, SubscribeStopVideoStreamingRequest& b) { + friend void swap(VideoStreaming& a, VideoStreaming& b) { a.Swap(&b); } - inline void Swap(SubscribeStopVideoStreamingRequest* other) { + inline void Swap(VideoStreaming* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1199,7 +1308,7 @@ class SubscribeStopVideoStreamingRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStopVideoStreamingRequest* other) { + void UnsafeArenaSwap(VideoStreaming* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1207,39 +1316,91 @@ class SubscribeStopVideoStreamingRequest final : // implements Message ---------------------------------------------- - SubscribeStopVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStopVideoStreamingRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + VideoStreaming* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStopVideoStreamingRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const VideoStreaming& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const VideoStreaming& from) { + VideoStreaming::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(VideoStreaming* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest"; + return "mavsdk.rpc.camera_server.VideoStreaming"; } protected: - explicit SubscribeStopVideoStreamingRequest(::google::protobuf::Arena* arena); - SubscribeStopVideoStreamingRequest(::google::protobuf::Arena* arena, const SubscribeStopVideoStreamingRequest& from); + explicit VideoStreaming(::google::protobuf::Arena* arena); + VideoStreaming(::google::protobuf::Arena* arena, const VideoStreaming& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) + enum : int { + kRtspUriFieldNumber = 2, + kHasRtspServerFieldNumber = 1, + }; + // string rtsp_uri = 2; + void clear_rtsp_uri() ; + const std::string& rtsp_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); + + private: + const std::string& _internal_rtsp_uri() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_rtsp_uri( + const std::string& value); + std::string* _internal_mutable_rtsp_uri(); + + public: + // bool has_rtsp_server = 1; + void clear_has_rtsp_server() ; + bool has_rtsp_server() const; + void set_has_rtsp_server(bool value); + + private: + bool _internal_has_rtsp_server() const; + void _internal_set_has_rtsp_server(bool value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.VideoStreaming) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 0, + 56, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -1254,30 +1415,35 @@ class SubscribeStopVideoStreamingRequest 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_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStopVideoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) */ { +class TakePhotoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.TakePhotoResponse) */ { public: - inline SubscribeStopVideoRequest() : SubscribeStopVideoRequest(nullptr) {} + inline TakePhotoResponse() : TakePhotoResponse(nullptr) {} + ~TakePhotoResponse() override; template - explicit PROTOBUF_CONSTEXPR SubscribeStopVideoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR TakePhotoResponse(::google::protobuf::internal::ConstantInitialized); - inline SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from) - : SubscribeStopVideoRequest(nullptr, from) {} - SubscribeStopVideoRequest(SubscribeStopVideoRequest&& from) noexcept - : SubscribeStopVideoRequest() { + inline TakePhotoResponse(const TakePhotoResponse& from) + : TakePhotoResponse(nullptr, from) {} + TakePhotoResponse(TakePhotoResponse&& from) noexcept + : TakePhotoResponse() { *this = ::std::move(from); } - inline SubscribeStopVideoRequest& operator=(const SubscribeStopVideoRequest& from) { + inline TakePhotoResponse& operator=(const TakePhotoResponse& from) { CopyFrom(from); return *this; } - inline SubscribeStopVideoRequest& operator=(SubscribeStopVideoRequest&& from) noexcept { + inline TakePhotoResponse& operator=(TakePhotoResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1309,20 +1475,20 @@ class SubscribeStopVideoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStopVideoRequest& default_instance() { + static const TakePhotoResponse& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStopVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStopVideoRequest_default_instance_); + static inline const TakePhotoResponse* internal_default_instance() { + return reinterpret_cast( + &_TakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 7; - friend void swap(SubscribeStopVideoRequest& a, SubscribeStopVideoRequest& b) { + friend void swap(TakePhotoResponse& a, TakePhotoResponse& b) { a.Swap(&b); } - inline void Swap(SubscribeStopVideoRequest* other) { + inline void Swap(TakePhotoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1335,7 +1501,7 @@ class SubscribeStopVideoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStopVideoRequest* other) { + void UnsafeArenaSwap(TakePhotoResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1343,39 +1509,74 @@ class SubscribeStopVideoRequest final : // implements Message ---------------------------------------------- - SubscribeStopVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStopVideoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + TakePhotoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStopVideoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const TakePhotoResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const TakePhotoResponse& from) { + TakePhotoResponse::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(TakePhotoResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStopVideoRequest"; + return "mavsdk.rpc.camera_server.TakePhotoResponse"; } protected: - explicit SubscribeStopVideoRequest(::google::protobuf::Arena* arena); - SubscribeStopVideoRequest(::google::protobuf::Arena* arena, const SubscribeStopVideoRequest& from); + explicit TakePhotoResponse(::google::protobuf::Arena* arena); + TakePhotoResponse(::google::protobuf::Arena* arena, const TakePhotoResponse& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) + enum : int { + kIndexFieldNumber = 1, + }; + // int32 index = 1; + void clear_index() ; + ::int32_t index() const; + void set_index(::int32_t value); + + private: + ::int32_t _internal_index() const; + void _internal_set_index(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.TakePhotoResponse) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -1390,30 +1591,33 @@ class SubscribeStopVideoRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t index_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStartVideoStreamingRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) */ { +class SubscribeZoomStopRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeZoomStopRequest) */ { public: - inline SubscribeStartVideoStreamingRequest() : SubscribeStartVideoStreamingRequest(nullptr) {} + inline SubscribeZoomStopRequest() : SubscribeZoomStopRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeStartVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeZoomStopRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeStartVideoStreamingRequest(const SubscribeStartVideoStreamingRequest& from) - : SubscribeStartVideoStreamingRequest(nullptr, from) {} - SubscribeStartVideoStreamingRequest(SubscribeStartVideoStreamingRequest&& from) noexcept - : SubscribeStartVideoStreamingRequest() { + inline SubscribeZoomStopRequest(const SubscribeZoomStopRequest& from) + : SubscribeZoomStopRequest(nullptr, from) {} + SubscribeZoomStopRequest(SubscribeZoomStopRequest&& from) noexcept + : SubscribeZoomStopRequest() { *this = ::std::move(from); } - inline SubscribeStartVideoStreamingRequest& operator=(const SubscribeStartVideoStreamingRequest& from) { + inline SubscribeZoomStopRequest& operator=(const SubscribeZoomStopRequest& from) { CopyFrom(from); return *this; } - inline SubscribeStartVideoStreamingRequest& operator=(SubscribeStartVideoStreamingRequest&& from) noexcept { + inline SubscribeZoomStopRequest& operator=(SubscribeZoomStopRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1445,20 +1649,20 @@ class SubscribeStartVideoStreamingRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStartVideoStreamingRequest& default_instance() { + static const SubscribeZoomStopRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStartVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStartVideoStreamingRequest_default_instance_); + static inline const SubscribeZoomStopRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeZoomStopRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 54; - friend void swap(SubscribeStartVideoStreamingRequest& a, SubscribeStartVideoStreamingRequest& b) { + friend void swap(SubscribeZoomStopRequest& a, SubscribeZoomStopRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeStartVideoStreamingRequest* other) { + inline void Swap(SubscribeZoomStopRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1471,7 +1675,7 @@ class SubscribeStartVideoStreamingRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStartVideoStreamingRequest* other) { + void UnsafeArenaSwap(SubscribeZoomStopRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1479,15 +1683,15 @@ class SubscribeStartVideoStreamingRequest final : // implements Message ---------------------------------------------- - SubscribeStartVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeZoomStopRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStartVideoStreamingRequest& from) { + inline void CopyFrom(const SubscribeZoomStopRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStartVideoStreamingRequest& from) { + void MergeFrom(const SubscribeZoomStopRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -1495,11 +1699,11 @@ class SubscribeStartVideoStreamingRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest"; + return "mavsdk.rpc.camera_server.SubscribeZoomStopRequest"; } protected: - explicit SubscribeStartVideoStreamingRequest(::google::protobuf::Arena* arena); - SubscribeStartVideoStreamingRequest(::google::protobuf::Arena* arena, const SubscribeStartVideoStreamingRequest& from); + explicit SubscribeZoomStopRequest(::google::protobuf::Arena* arena); + SubscribeZoomStopRequest(::google::protobuf::Arena* arena, const SubscribeZoomStopRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -1508,7 +1712,7 @@ class SubscribeStartVideoStreamingRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeZoomStopRequest) private: class _Internal; @@ -1531,25 +1735,25 @@ class SubscribeStartVideoStreamingRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStartVideoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) */ { +class SubscribeZoomRangeRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeZoomRangeRequest) */ { public: - inline SubscribeStartVideoRequest() : SubscribeStartVideoRequest(nullptr) {} + inline SubscribeZoomRangeRequest() : SubscribeZoomRangeRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeStartVideoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeZoomRangeRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from) - : SubscribeStartVideoRequest(nullptr, from) {} - SubscribeStartVideoRequest(SubscribeStartVideoRequest&& from) noexcept - : SubscribeStartVideoRequest() { + inline SubscribeZoomRangeRequest(const SubscribeZoomRangeRequest& from) + : SubscribeZoomRangeRequest(nullptr, from) {} + SubscribeZoomRangeRequest(SubscribeZoomRangeRequest&& from) noexcept + : SubscribeZoomRangeRequest() { *this = ::std::move(from); } - inline SubscribeStartVideoRequest& operator=(const SubscribeStartVideoRequest& from) { + inline SubscribeZoomRangeRequest& operator=(const SubscribeZoomRangeRequest& from) { CopyFrom(from); return *this; } - inline SubscribeStartVideoRequest& operator=(SubscribeStartVideoRequest&& from) noexcept { + inline SubscribeZoomRangeRequest& operator=(SubscribeZoomRangeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1581,20 +1785,20 @@ class SubscribeStartVideoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStartVideoRequest& default_instance() { + static const SubscribeZoomRangeRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStartVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStartVideoRequest_default_instance_); + static inline const SubscribeZoomRangeRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeZoomRangeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 58; - friend void swap(SubscribeStartVideoRequest& a, SubscribeStartVideoRequest& b) { + friend void swap(SubscribeZoomRangeRequest& a, SubscribeZoomRangeRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeStartVideoRequest* other) { + inline void Swap(SubscribeZoomRangeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1607,7 +1811,7 @@ class SubscribeStartVideoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStartVideoRequest* other) { + void UnsafeArenaSwap(SubscribeZoomRangeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1615,15 +1819,15 @@ class SubscribeStartVideoRequest final : // implements Message ---------------------------------------------- - SubscribeStartVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeZoomRangeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStartVideoRequest& from) { + inline void CopyFrom(const SubscribeZoomRangeRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStartVideoRequest& from) { + void MergeFrom(const SubscribeZoomRangeRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -1631,11 +1835,11 @@ class SubscribeStartVideoRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStartVideoRequest"; + return "mavsdk.rpc.camera_server.SubscribeZoomRangeRequest"; } protected: - explicit SubscribeStartVideoRequest(::google::protobuf::Arena* arena); - SubscribeStartVideoRequest(::google::protobuf::Arena* arena, const SubscribeStartVideoRequest& from); + explicit SubscribeZoomRangeRequest(::google::protobuf::Arena* arena); + SubscribeZoomRangeRequest(::google::protobuf::Arena* arena, const SubscribeZoomRangeRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -1644,7 +1848,7 @@ class SubscribeStartVideoRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeZoomRangeRequest) private: class _Internal; @@ -1667,25 +1871,25 @@ class SubscribeStartVideoRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeSetModeRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeSetModeRequest) */ { +class SubscribeZoomOutStartRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeZoomOutStartRequest) */ { public: - inline SubscribeSetModeRequest() : SubscribeSetModeRequest(nullptr) {} + inline SubscribeZoomOutStartRequest() : SubscribeZoomOutStartRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeSetModeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeZoomOutStartRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeSetModeRequest(const SubscribeSetModeRequest& from) - : SubscribeSetModeRequest(nullptr, from) {} - SubscribeSetModeRequest(SubscribeSetModeRequest&& from) noexcept - : SubscribeSetModeRequest() { + inline SubscribeZoomOutStartRequest(const SubscribeZoomOutStartRequest& from) + : SubscribeZoomOutStartRequest(nullptr, from) {} + SubscribeZoomOutStartRequest(SubscribeZoomOutStartRequest&& from) noexcept + : SubscribeZoomOutStartRequest() { *this = ::std::move(from); } - inline SubscribeSetModeRequest& operator=(const SubscribeSetModeRequest& from) { + inline SubscribeZoomOutStartRequest& operator=(const SubscribeZoomOutStartRequest& from) { CopyFrom(from); return *this; } - inline SubscribeSetModeRequest& operator=(SubscribeSetModeRequest&& from) noexcept { + inline SubscribeZoomOutStartRequest& operator=(SubscribeZoomOutStartRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1717,20 +1921,20 @@ class SubscribeSetModeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeSetModeRequest& default_instance() { + static const SubscribeZoomOutStartRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeSetModeRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeSetModeRequest_default_instance_); + static inline const SubscribeZoomOutStartRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeZoomOutStartRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 26; + 50; - friend void swap(SubscribeSetModeRequest& a, SubscribeSetModeRequest& b) { + friend void swap(SubscribeZoomOutStartRequest& a, SubscribeZoomOutStartRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeSetModeRequest* other) { + inline void Swap(SubscribeZoomOutStartRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1743,7 +1947,7 @@ class SubscribeSetModeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeSetModeRequest* other) { + void UnsafeArenaSwap(SubscribeZoomOutStartRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1751,15 +1955,15 @@ class SubscribeSetModeRequest final : // implements Message ---------------------------------------------- - SubscribeSetModeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeZoomOutStartRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeSetModeRequest& from) { + inline void CopyFrom(const SubscribeZoomOutStartRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeSetModeRequest& from) { + void MergeFrom(const SubscribeZoomOutStartRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -1767,11 +1971,11 @@ class SubscribeSetModeRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeSetModeRequest"; + return "mavsdk.rpc.camera_server.SubscribeZoomOutStartRequest"; } protected: - explicit SubscribeSetModeRequest(::google::protobuf::Arena* arena); - SubscribeSetModeRequest(::google::protobuf::Arena* arena, const SubscribeSetModeRequest& from); + explicit SubscribeZoomOutStartRequest(::google::protobuf::Arena* arena); + SubscribeZoomOutStartRequest(::google::protobuf::Arena* arena, const SubscribeZoomOutStartRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -1780,7 +1984,7 @@ class SubscribeSetModeRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeSetModeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeZoomOutStartRequest) private: class _Internal; @@ -1803,25 +2007,25 @@ class SubscribeSetModeRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeResetSettingsRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) */ { +class SubscribeZoomInStartRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeZoomInStartRequest) */ { public: - inline SubscribeResetSettingsRequest() : SubscribeResetSettingsRequest(nullptr) {} + inline SubscribeZoomInStartRequest() : SubscribeZoomInStartRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeResetSettingsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeZoomInStartRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeResetSettingsRequest(const SubscribeResetSettingsRequest& from) - : SubscribeResetSettingsRequest(nullptr, from) {} - SubscribeResetSettingsRequest(SubscribeResetSettingsRequest&& from) noexcept - : SubscribeResetSettingsRequest() { + inline SubscribeZoomInStartRequest(const SubscribeZoomInStartRequest& from) + : SubscribeZoomInStartRequest(nullptr, from) {} + SubscribeZoomInStartRequest(SubscribeZoomInStartRequest&& from) noexcept + : SubscribeZoomInStartRequest() { *this = ::std::move(from); } - inline SubscribeResetSettingsRequest& operator=(const SubscribeResetSettingsRequest& from) { + inline SubscribeZoomInStartRequest& operator=(const SubscribeZoomInStartRequest& from) { CopyFrom(from); return *this; } - inline SubscribeResetSettingsRequest& operator=(SubscribeResetSettingsRequest&& from) noexcept { + inline SubscribeZoomInStartRequest& operator=(SubscribeZoomInStartRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1853,20 +2057,20 @@ class SubscribeResetSettingsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeResetSettingsRequest& default_instance() { + static const SubscribeZoomInStartRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeResetSettingsRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeResetSettingsRequest_default_instance_); + static inline const SubscribeZoomInStartRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeZoomInStartRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 42; + 46; - friend void swap(SubscribeResetSettingsRequest& a, SubscribeResetSettingsRequest& b) { + friend void swap(SubscribeZoomInStartRequest& a, SubscribeZoomInStartRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeResetSettingsRequest* other) { + inline void Swap(SubscribeZoomInStartRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1879,7 +2083,7 @@ class SubscribeResetSettingsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeResetSettingsRequest* other) { + void UnsafeArenaSwap(SubscribeZoomInStartRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1887,15 +2091,15 @@ class SubscribeResetSettingsRequest final : // implements Message ---------------------------------------------- - SubscribeResetSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeZoomInStartRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeResetSettingsRequest& from) { + inline void CopyFrom(const SubscribeZoomInStartRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeResetSettingsRequest& from) { + void MergeFrom(const SubscribeZoomInStartRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -1903,11 +2107,11 @@ class SubscribeResetSettingsRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeResetSettingsRequest"; + return "mavsdk.rpc.camera_server.SubscribeZoomInStartRequest"; } protected: - explicit SubscribeResetSettingsRequest(::google::protobuf::Arena* arena); - SubscribeResetSettingsRequest(::google::protobuf::Arena* arena, const SubscribeResetSettingsRequest& from); + explicit SubscribeZoomInStartRequest(::google::protobuf::Arena* arena); + SubscribeZoomInStartRequest(::google::protobuf::Arena* arena, const SubscribeZoomInStartRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -1916,7 +2120,7 @@ class SubscribeResetSettingsRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeZoomInStartRequest) private: class _Internal; @@ -1939,25 +2143,25 @@ class SubscribeResetSettingsRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeFormatStorageRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) */ { +class SubscribeTakePhotoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) */ { public: - inline SubscribeFormatStorageRequest() : SubscribeFormatStorageRequest(nullptr) {} + inline SubscribeTakePhotoRequest() : SubscribeTakePhotoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeFormatStorageRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeTakePhotoRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeFormatStorageRequest(const SubscribeFormatStorageRequest& from) - : SubscribeFormatStorageRequest(nullptr, from) {} - SubscribeFormatStorageRequest(SubscribeFormatStorageRequest&& from) noexcept - : SubscribeFormatStorageRequest() { + inline SubscribeTakePhotoRequest(const SubscribeTakePhotoRequest& from) + : SubscribeTakePhotoRequest(nullptr, from) {} + SubscribeTakePhotoRequest(SubscribeTakePhotoRequest&& from) noexcept + : SubscribeTakePhotoRequest() { *this = ::std::move(from); } - inline SubscribeFormatStorageRequest& operator=(const SubscribeFormatStorageRequest& from) { + inline SubscribeTakePhotoRequest& operator=(const SubscribeTakePhotoRequest& from) { CopyFrom(from); return *this; } - inline SubscribeFormatStorageRequest& operator=(SubscribeFormatStorageRequest&& from) noexcept { + inline SubscribeTakePhotoRequest& operator=(SubscribeTakePhotoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1989,20 +2193,20 @@ class SubscribeFormatStorageRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeFormatStorageRequest& default_instance() { + static const SubscribeTakePhotoRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeFormatStorageRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeFormatStorageRequest_default_instance_); + static inline const SubscribeTakePhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 38; + 6; - friend void swap(SubscribeFormatStorageRequest& a, SubscribeFormatStorageRequest& b) { + friend void swap(SubscribeTakePhotoRequest& a, SubscribeTakePhotoRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeFormatStorageRequest* other) { + inline void Swap(SubscribeTakePhotoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2015,7 +2219,7 @@ class SubscribeFormatStorageRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeFormatStorageRequest* other) { + void UnsafeArenaSwap(SubscribeTakePhotoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2023,15 +2227,15 @@ class SubscribeFormatStorageRequest final : // implements Message ---------------------------------------------- - SubscribeFormatStorageRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeTakePhotoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeFormatStorageRequest& from) { + inline void CopyFrom(const SubscribeTakePhotoRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeFormatStorageRequest& from) { + void MergeFrom(const SubscribeTakePhotoRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2039,11 +2243,11 @@ class SubscribeFormatStorageRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeFormatStorageRequest"; + return "mavsdk.rpc.camera_server.SubscribeTakePhotoRequest"; } protected: - explicit SubscribeFormatStorageRequest(::google::protobuf::Arena* arena); - SubscribeFormatStorageRequest(::google::protobuf::Arena* arena, const SubscribeFormatStorageRequest& from); + explicit SubscribeTakePhotoRequest(::google::protobuf::Arena* arena); + SubscribeTakePhotoRequest(::google::protobuf::Arena* arena, const SubscribeTakePhotoRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -2052,7 +2256,7 @@ class SubscribeFormatStorageRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) private: class _Internal; @@ -2075,25 +2279,25 @@ class SubscribeFormatStorageRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeCaptureStatusRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) */ { +class SubscribeStorageInformationRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) */ { public: - inline SubscribeCaptureStatusRequest() : SubscribeCaptureStatusRequest(nullptr) {} + inline SubscribeStorageInformationRequest() : SubscribeStorageInformationRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeCaptureStatusRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStorageInformationRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeCaptureStatusRequest(const SubscribeCaptureStatusRequest& from) - : SubscribeCaptureStatusRequest(nullptr, from) {} - SubscribeCaptureStatusRequest(SubscribeCaptureStatusRequest&& from) noexcept - : SubscribeCaptureStatusRequest() { + inline SubscribeStorageInformationRequest(const SubscribeStorageInformationRequest& from) + : SubscribeStorageInformationRequest(nullptr, from) {} + SubscribeStorageInformationRequest(SubscribeStorageInformationRequest&& from) noexcept + : SubscribeStorageInformationRequest() { *this = ::std::move(from); } - inline SubscribeCaptureStatusRequest& operator=(const SubscribeCaptureStatusRequest& from) { + inline SubscribeStorageInformationRequest& operator=(const SubscribeStorageInformationRequest& from) { CopyFrom(from); return *this; } - inline SubscribeCaptureStatusRequest& operator=(SubscribeCaptureStatusRequest&& from) noexcept { + inline SubscribeStorageInformationRequest& operator=(SubscribeStorageInformationRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2125,20 +2329,20 @@ class SubscribeCaptureStatusRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeCaptureStatusRequest& default_instance() { + static const SubscribeStorageInformationRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeCaptureStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeCaptureStatusRequest_default_instance_); + static inline const SubscribeStorageInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStorageInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 34; + 30; - friend void swap(SubscribeCaptureStatusRequest& a, SubscribeCaptureStatusRequest& b) { + friend void swap(SubscribeStorageInformationRequest& a, SubscribeStorageInformationRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeCaptureStatusRequest* other) { + inline void Swap(SubscribeStorageInformationRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2151,7 +2355,7 @@ class SubscribeCaptureStatusRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeCaptureStatusRequest* other) { + void UnsafeArenaSwap(SubscribeStorageInformationRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2159,15 +2363,15 @@ class SubscribeCaptureStatusRequest final : // implements Message ---------------------------------------------- - SubscribeCaptureStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStorageInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeCaptureStatusRequest& from) { + inline void CopyFrom(const SubscribeStorageInformationRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeCaptureStatusRequest& from) { + void MergeFrom(const SubscribeStorageInformationRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2175,11 +2379,11 @@ class SubscribeCaptureStatusRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest"; + return "mavsdk.rpc.camera_server.SubscribeStorageInformationRequest"; } protected: - explicit SubscribeCaptureStatusRequest(::google::protobuf::Arena* arena); - SubscribeCaptureStatusRequest(::google::protobuf::Arena* arena, const SubscribeCaptureStatusRequest& from); + explicit SubscribeStorageInformationRequest(::google::protobuf::Arena* arena); + SubscribeStorageInformationRequest(::google::protobuf::Arena* arena, const SubscribeStorageInformationRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -2188,7 +2392,7 @@ class SubscribeCaptureStatusRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) private: class _Internal; @@ -2211,26 +2415,25 @@ class SubscribeCaptureStatusRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StorageInformationResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformationResponse) */ { +class SubscribeStopVideoStreamingRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) */ { public: - inline StorageInformationResponse() : StorageInformationResponse(nullptr) {} - ~StorageInformationResponse() override; + inline SubscribeStopVideoStreamingRequest() : SubscribeStopVideoStreamingRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StorageInformationResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStopVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); - inline StorageInformationResponse(const StorageInformationResponse& from) - : StorageInformationResponse(nullptr, from) {} - StorageInformationResponse(StorageInformationResponse&& from) noexcept - : StorageInformationResponse() { + inline SubscribeStopVideoStreamingRequest(const SubscribeStopVideoStreamingRequest& from) + : SubscribeStopVideoStreamingRequest(nullptr, from) {} + SubscribeStopVideoStreamingRequest(SubscribeStopVideoStreamingRequest&& from) noexcept + : SubscribeStopVideoStreamingRequest() { *this = ::std::move(from); } - inline StorageInformationResponse& operator=(const StorageInformationResponse& from) { + inline SubscribeStopVideoStreamingRequest& operator=(const SubscribeStopVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline StorageInformationResponse& operator=(StorageInformationResponse&& from) noexcept { + inline SubscribeStopVideoStreamingRequest& operator=(SubscribeStopVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2262,20 +2465,20 @@ class StorageInformationResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StorageInformationResponse& default_instance() { + static const SubscribeStopVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const StorageInformationResponse* internal_default_instance() { - return reinterpret_cast( - &_StorageInformationResponse_default_instance_); + static inline const SubscribeStopVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStopVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 31; + 22; - friend void swap(StorageInformationResponse& a, StorageInformationResponse& b) { + friend void swap(SubscribeStopVideoStreamingRequest& a, SubscribeStopVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(StorageInformationResponse* other) { + inline void Swap(SubscribeStopVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2288,7 +2491,7 @@ class StorageInformationResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StorageInformationResponse* other) { + void UnsafeArenaSwap(SubscribeStopVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2296,74 +2499,39 @@ class StorageInformationResponse final : // implements Message ---------------------------------------------- - StorageInformationResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStopVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StorageInformationResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StorageInformationResponse& from) { - StorageInformationResponse::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStopVideoStreamingRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStopVideoStreamingRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StorageInformationResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StorageInformationResponse"; + return "mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest"; } protected: - explicit StorageInformationResponse(::google::protobuf::Arena* arena); - StorageInformationResponse(::google::protobuf::Arena* arena, const StorageInformationResponse& from); + explicit SubscribeStopVideoStreamingRequest(::google::protobuf::Arena* arena); + SubscribeStopVideoStreamingRequest(::google::protobuf::Arena* arena, const SubscribeStopVideoStreamingRequest& 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 { - kStorageIdFieldNumber = 1, - }; - // int32 storage_id = 1; - void clear_storage_id() ; - ::int32_t storage_id() const; - void set_storage_id(::int32_t value); - - private: - ::int32_t _internal_storage_id() const; - void _internal_set_storage_id(::int32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformationResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, - 0, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -2378,34 +2546,30 @@ class StorageInformationResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t storage_id_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StorageInformation final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformation) */ { +class SubscribeStopVideoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) */ { public: - inline StorageInformation() : StorageInformation(nullptr) {} - ~StorageInformation() override; + inline SubscribeStopVideoRequest() : SubscribeStopVideoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StorageInformation(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStopVideoRequest(::google::protobuf::internal::ConstantInitialized); - inline StorageInformation(const StorageInformation& from) - : StorageInformation(nullptr, from) {} - StorageInformation(StorageInformation&& from) noexcept - : StorageInformation() { + inline SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from) + : SubscribeStopVideoRequest(nullptr, from) {} + SubscribeStopVideoRequest(SubscribeStopVideoRequest&& from) noexcept + : SubscribeStopVideoRequest() { *this = ::std::move(from); } - inline StorageInformation& operator=(const StorageInformation& from) { + inline SubscribeStopVideoRequest& operator=(const SubscribeStopVideoRequest& from) { CopyFrom(from); return *this; } - inline StorageInformation& operator=(StorageInformation&& from) noexcept { + inline SubscribeStopVideoRequest& operator=(SubscribeStopVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2437,20 +2601,20 @@ class StorageInformation final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StorageInformation& default_instance() { + static const SubscribeStopVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const StorageInformation* internal_default_instance() { - return reinterpret_cast( - &_StorageInformation_default_instance_); + static inline const SubscribeStopVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStopVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 52; + 14; - friend void swap(StorageInformation& a, StorageInformation& b) { + friend void swap(SubscribeStopVideoRequest& a, SubscribeStopVideoRequest& b) { a.Swap(&b); } - inline void Swap(StorageInformation* other) { + inline void Swap(SubscribeStopVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2463,7 +2627,7 @@ class StorageInformation final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StorageInformation* other) { + void UnsafeArenaSwap(SubscribeStopVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2471,197 +2635,39 @@ class StorageInformation final : // implements Message ---------------------------------------------- - StorageInformation* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStopVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StorageInformation& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StorageInformation& from) { - StorageInformation::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStopVideoRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStopVideoRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StorageInformation* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StorageInformation"; + return "mavsdk.rpc.camera_server.SubscribeStopVideoRequest"; } protected: - explicit StorageInformation(::google::protobuf::Arena* arena); - StorageInformation(::google::protobuf::Arena* arena, const StorageInformation& from); + explicit SubscribeStopVideoRequest(::google::protobuf::Arena* arena); + SubscribeStopVideoRequest(::google::protobuf::Arena* arena, const SubscribeStopVideoRequest& from); public: - static const ClassData _class_data_; - const ::google::protobuf::Message::ClassData*GetClassData() const final; - ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- - using StorageStatus = StorageInformation_StorageStatus; - static constexpr StorageStatus STORAGE_STATUS_NOT_AVAILABLE = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE; - static constexpr StorageStatus STORAGE_STATUS_UNFORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_UNFORMATTED; - static constexpr StorageStatus STORAGE_STATUS_FORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_FORMATTED; - static constexpr StorageStatus STORAGE_STATUS_NOT_SUPPORTED = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED; - static inline bool StorageStatus_IsValid(int value) { - return StorageInformation_StorageStatus_IsValid(value); - } - static constexpr StorageStatus StorageStatus_MIN = StorageInformation_StorageStatus_StorageStatus_MIN; - static constexpr StorageStatus StorageStatus_MAX = StorageInformation_StorageStatus_StorageStatus_MAX; - static constexpr int StorageStatus_ARRAYSIZE = StorageInformation_StorageStatus_StorageStatus_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* StorageStatus_descriptor() { - return StorageInformation_StorageStatus_descriptor(); - } - template - static inline const std::string& StorageStatus_Name(T value) { - return StorageInformation_StorageStatus_Name(value); - } - static inline bool StorageStatus_Parse(absl::string_view name, StorageStatus* value) { - return StorageInformation_StorageStatus_Parse(name, value); - } - - using StorageType = StorageInformation_StorageType; - static constexpr StorageType STORAGE_TYPE_UNKNOWN = StorageInformation_StorageType_STORAGE_TYPE_UNKNOWN; - static constexpr StorageType STORAGE_TYPE_USB_STICK = StorageInformation_StorageType_STORAGE_TYPE_USB_STICK; - static constexpr StorageType STORAGE_TYPE_SD = StorageInformation_StorageType_STORAGE_TYPE_SD; - static constexpr StorageType STORAGE_TYPE_MICROSD = StorageInformation_StorageType_STORAGE_TYPE_MICROSD; - static constexpr StorageType STORAGE_TYPE_HD = StorageInformation_StorageType_STORAGE_TYPE_HD; - static constexpr StorageType STORAGE_TYPE_OTHER = StorageInformation_StorageType_STORAGE_TYPE_OTHER; - static inline bool StorageType_IsValid(int value) { - return StorageInformation_StorageType_IsValid(value); - } - static constexpr StorageType StorageType_MIN = StorageInformation_StorageType_StorageType_MIN; - static constexpr StorageType StorageType_MAX = StorageInformation_StorageType_StorageType_MAX; - static constexpr int StorageType_ARRAYSIZE = StorageInformation_StorageType_StorageType_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* StorageType_descriptor() { - return StorageInformation_StorageType_descriptor(); - } - template - static inline const std::string& StorageType_Name(T value) { - return StorageInformation_StorageType_Name(value); - } - static inline bool StorageType_Parse(absl::string_view name, StorageType* value) { - return StorageInformation_StorageType_Parse(name, value); - } - // accessors ------------------------------------------------------- - enum : int { - kUsedStorageMibFieldNumber = 1, - kAvailableStorageMibFieldNumber = 2, - kTotalStorageMibFieldNumber = 3, - kStorageStatusFieldNumber = 4, - kStorageIdFieldNumber = 5, - kStorageTypeFieldNumber = 6, - kReadSpeedMibSFieldNumber = 7, - kWriteSpeedMibSFieldNumber = 8, - }; - // float used_storage_mib = 1; - void clear_used_storage_mib() ; - float used_storage_mib() const; - void set_used_storage_mib(float value); - - private: - float _internal_used_storage_mib() const; - void _internal_set_used_storage_mib(float value); - - public: - // float available_storage_mib = 2; - void clear_available_storage_mib() ; - float available_storage_mib() const; - void set_available_storage_mib(float value); - - private: - float _internal_available_storage_mib() const; - void _internal_set_available_storage_mib(float value); - - public: - // float total_storage_mib = 3; - void clear_total_storage_mib() ; - float total_storage_mib() const; - void set_total_storage_mib(float value); - - private: - float _internal_total_storage_mib() const; - void _internal_set_total_storage_mib(float value); - - public: - // .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; - void clear_storage_status() ; - ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus storage_status() const; - void set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); - - private: - ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus _internal_storage_status() const; - void _internal_set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); - - public: - // uint32 storage_id = 5; - void clear_storage_id() ; - ::uint32_t storage_id() const; - void set_storage_id(::uint32_t value); - - private: - ::uint32_t _internal_storage_id() const; - void _internal_set_storage_id(::uint32_t value); - - public: - // .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; - void clear_storage_type() ; - ::mavsdk::rpc::camera_server::StorageInformation_StorageType storage_type() const; - void set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); - - private: - ::mavsdk::rpc::camera_server::StorageInformation_StorageType _internal_storage_type() const; - void _internal_set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); - - public: - // float read_speed_mib_s = 7; - void clear_read_speed_mib_s() ; - float read_speed_mib_s() const; - void set_read_speed_mib_s(float value); - - private: - float _internal_read_speed_mib_s() const; - void _internal_set_read_speed_mib_s(float value); - - public: - // float write_speed_mib_s = 8; - void clear_write_speed_mib_s() ; - float write_speed_mib_s() const; - void set_write_speed_mib_s(float value); - - private: - float _internal_write_speed_mib_s() const; - void _internal_set_write_speed_mib_s(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformation) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 3, 8, 0, - 0, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -2676,41 +2682,30 @@ class StorageInformation final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float used_storage_mib_; - float available_storage_mib_; - float total_storage_mib_; - int storage_status_; - ::uint32_t storage_id_; - int storage_type_; - float read_speed_mib_s_; - float write_speed_mib_s_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StopVideoStreamingResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoStreamingResponse) */ { +class SubscribeStartVideoStreamingRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) */ { public: - inline StopVideoStreamingResponse() : StopVideoStreamingResponse(nullptr) {} - ~StopVideoStreamingResponse() override; + inline SubscribeStartVideoStreamingRequest() : SubscribeStartVideoStreamingRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StopVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStartVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); - inline StopVideoStreamingResponse(const StopVideoStreamingResponse& from) - : StopVideoStreamingResponse(nullptr, from) {} - StopVideoStreamingResponse(StopVideoStreamingResponse&& from) noexcept - : StopVideoStreamingResponse() { + inline SubscribeStartVideoStreamingRequest(const SubscribeStartVideoStreamingRequest& from) + : SubscribeStartVideoStreamingRequest(nullptr, from) {} + SubscribeStartVideoStreamingRequest(SubscribeStartVideoStreamingRequest&& from) noexcept + : SubscribeStartVideoStreamingRequest() { *this = ::std::move(from); } - inline StopVideoStreamingResponse& operator=(const StopVideoStreamingResponse& from) { + inline SubscribeStartVideoStreamingRequest& operator=(const SubscribeStartVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline StopVideoStreamingResponse& operator=(StopVideoStreamingResponse&& from) noexcept { + inline SubscribeStartVideoStreamingRequest& operator=(SubscribeStartVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2742,20 +2737,20 @@ class StopVideoStreamingResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StopVideoStreamingResponse& default_instance() { + static const SubscribeStartVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const StopVideoStreamingResponse* internal_default_instance() { - return reinterpret_cast( - &_StopVideoStreamingResponse_default_instance_); + static inline const SubscribeStartVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStartVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 23; + 18; - friend void swap(StopVideoStreamingResponse& a, StopVideoStreamingResponse& b) { + friend void swap(SubscribeStartVideoStreamingRequest& a, SubscribeStartVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(StopVideoStreamingResponse* other) { + inline void Swap(SubscribeStartVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2768,7 +2763,7 @@ class StopVideoStreamingResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StopVideoStreamingResponse* other) { + void UnsafeArenaSwap(SubscribeStartVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2776,74 +2771,39 @@ class StopVideoStreamingResponse final : // implements Message ---------------------------------------------- - StopVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStartVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StopVideoStreamingResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StopVideoStreamingResponse& from) { - StopVideoStreamingResponse::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStartVideoStreamingRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStartVideoStreamingRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StopVideoStreamingResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StopVideoStreamingResponse"; + return "mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest"; } protected: - explicit StopVideoStreamingResponse(::google::protobuf::Arena* arena); - StopVideoStreamingResponse(::google::protobuf::Arena* arena, const StopVideoStreamingResponse& from); + explicit SubscribeStartVideoStreamingRequest(::google::protobuf::Arena* arena); + SubscribeStartVideoStreamingRequest(::google::protobuf::Arena* arena, const SubscribeStartVideoStreamingRequest& 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 { - kStreamIdFieldNumber = 1, - }; - // 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: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, - 0, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -2858,34 +2818,30 @@ class StopVideoStreamingResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t stream_id_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StopVideoResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoResponse) */ { +class SubscribeStartVideoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) */ { public: - inline StopVideoResponse() : StopVideoResponse(nullptr) {} - ~StopVideoResponse() override; + inline SubscribeStartVideoRequest() : SubscribeStartVideoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StopVideoResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStartVideoRequest(::google::protobuf::internal::ConstantInitialized); - inline StopVideoResponse(const StopVideoResponse& from) - : StopVideoResponse(nullptr, from) {} - StopVideoResponse(StopVideoResponse&& from) noexcept - : StopVideoResponse() { + inline SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from) + : SubscribeStartVideoRequest(nullptr, from) {} + SubscribeStartVideoRequest(SubscribeStartVideoRequest&& from) noexcept + : SubscribeStartVideoRequest() { *this = ::std::move(from); } - inline StopVideoResponse& operator=(const StopVideoResponse& from) { + inline SubscribeStartVideoRequest& operator=(const SubscribeStartVideoRequest& from) { CopyFrom(from); return *this; } - inline StopVideoResponse& operator=(StopVideoResponse&& from) noexcept { + inline SubscribeStartVideoRequest& operator=(SubscribeStartVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2917,20 +2873,20 @@ class StopVideoResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StopVideoResponse& default_instance() { + static const SubscribeStartVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const StopVideoResponse* internal_default_instance() { - return reinterpret_cast( - &_StopVideoResponse_default_instance_); + static inline const SubscribeStartVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStartVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 10; - friend void swap(StopVideoResponse& a, StopVideoResponse& b) { + friend void swap(SubscribeStartVideoRequest& a, SubscribeStartVideoRequest& b) { a.Swap(&b); } - inline void Swap(StopVideoResponse* other) { + inline void Swap(SubscribeStartVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2943,7 +2899,7 @@ class StopVideoResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StopVideoResponse* other) { + void UnsafeArenaSwap(SubscribeStartVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2951,74 +2907,39 @@ class StopVideoResponse final : // implements Message ---------------------------------------------- - StopVideoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStartVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StopVideoResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StopVideoResponse& from) { - StopVideoResponse::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStartVideoRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStartVideoRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StopVideoResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StopVideoResponse"; + return "mavsdk.rpc.camera_server.SubscribeStartVideoRequest"; } protected: - explicit StopVideoResponse(::google::protobuf::Arena* arena); - StopVideoResponse(::google::protobuf::Arena* arena, const StopVideoResponse& from); + explicit SubscribeStartVideoRequest(::google::protobuf::Arena* arena); + SubscribeStartVideoRequest(::google::protobuf::Arena* arena, const SubscribeStartVideoRequest& 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 { - kStreamIdFieldNumber = 1, - }; - // 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: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, - 0, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -3033,34 +2954,30 @@ class StopVideoResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t stream_id_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StartVideoStreamingResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoStreamingResponse) */ { +class SubscribeSetModeRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeSetModeRequest) */ { public: - inline StartVideoStreamingResponse() : StartVideoStreamingResponse(nullptr) {} - ~StartVideoStreamingResponse() override; + inline SubscribeSetModeRequest() : SubscribeSetModeRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StartVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeSetModeRequest(::google::protobuf::internal::ConstantInitialized); - inline StartVideoStreamingResponse(const StartVideoStreamingResponse& from) - : StartVideoStreamingResponse(nullptr, from) {} - StartVideoStreamingResponse(StartVideoStreamingResponse&& from) noexcept - : StartVideoStreamingResponse() { + inline SubscribeSetModeRequest(const SubscribeSetModeRequest& from) + : SubscribeSetModeRequest(nullptr, from) {} + SubscribeSetModeRequest(SubscribeSetModeRequest&& from) noexcept + : SubscribeSetModeRequest() { *this = ::std::move(from); } - inline StartVideoStreamingResponse& operator=(const StartVideoStreamingResponse& from) { + inline SubscribeSetModeRequest& operator=(const SubscribeSetModeRequest& from) { CopyFrom(from); return *this; } - inline StartVideoStreamingResponse& operator=(StartVideoStreamingResponse&& from) noexcept { + inline SubscribeSetModeRequest& operator=(SubscribeSetModeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3092,20 +3009,20 @@ class StartVideoStreamingResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StartVideoStreamingResponse& default_instance() { + static const SubscribeSetModeRequest& default_instance() { return *internal_default_instance(); } - static inline const StartVideoStreamingResponse* internal_default_instance() { - return reinterpret_cast( - &_StartVideoStreamingResponse_default_instance_); + static inline const SubscribeSetModeRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeSetModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 19; + 26; - friend void swap(StartVideoStreamingResponse& a, StartVideoStreamingResponse& b) { + friend void swap(SubscribeSetModeRequest& a, SubscribeSetModeRequest& b) { a.Swap(&b); } - inline void Swap(StartVideoStreamingResponse* other) { + inline void Swap(SubscribeSetModeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3118,7 +3035,7 @@ class StartVideoStreamingResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StartVideoStreamingResponse* other) { + void UnsafeArenaSwap(SubscribeSetModeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3126,74 +3043,39 @@ class StartVideoStreamingResponse final : // implements Message ---------------------------------------------- - StartVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeSetModeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StartVideoStreamingResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StartVideoStreamingResponse& from) { - StartVideoStreamingResponse::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeSetModeRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeSetModeRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StartVideoStreamingResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StartVideoStreamingResponse"; + return "mavsdk.rpc.camera_server.SubscribeSetModeRequest"; } protected: - explicit StartVideoStreamingResponse(::google::protobuf::Arena* arena); - StartVideoStreamingResponse(::google::protobuf::Arena* arena, const StartVideoStreamingResponse& from); + explicit SubscribeSetModeRequest(::google::protobuf::Arena* arena); + SubscribeSetModeRequest(::google::protobuf::Arena* arena, const SubscribeSetModeRequest& 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 { - kStreamIdFieldNumber = 1, - }; - // 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: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeSetModeRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, - 0, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -3208,34 +3090,30 @@ class StartVideoStreamingResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t stream_id_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StartVideoResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoResponse) */ { +class SubscribeResetSettingsRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) */ { public: - inline StartVideoResponse() : StartVideoResponse(nullptr) {} - ~StartVideoResponse() override; + inline SubscribeResetSettingsRequest() : SubscribeResetSettingsRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StartVideoResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeResetSettingsRequest(::google::protobuf::internal::ConstantInitialized); - inline StartVideoResponse(const StartVideoResponse& from) - : StartVideoResponse(nullptr, from) {} - StartVideoResponse(StartVideoResponse&& from) noexcept - : StartVideoResponse() { + inline SubscribeResetSettingsRequest(const SubscribeResetSettingsRequest& from) + : SubscribeResetSettingsRequest(nullptr, from) {} + SubscribeResetSettingsRequest(SubscribeResetSettingsRequest&& from) noexcept + : SubscribeResetSettingsRequest() { *this = ::std::move(from); } - inline StartVideoResponse& operator=(const StartVideoResponse& from) { + inline SubscribeResetSettingsRequest& operator=(const SubscribeResetSettingsRequest& from) { CopyFrom(from); return *this; } - inline StartVideoResponse& operator=(StartVideoResponse&& from) noexcept { + inline SubscribeResetSettingsRequest& operator=(SubscribeResetSettingsRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3267,20 +3145,20 @@ class StartVideoResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StartVideoResponse& default_instance() { + static const SubscribeResetSettingsRequest& default_instance() { return *internal_default_instance(); } - static inline const StartVideoResponse* internal_default_instance() { - return reinterpret_cast( - &_StartVideoResponse_default_instance_); + static inline const SubscribeResetSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeResetSettingsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 11; + 42; - friend void swap(StartVideoResponse& a, StartVideoResponse& b) { + friend void swap(SubscribeResetSettingsRequest& a, SubscribeResetSettingsRequest& b) { a.Swap(&b); } - inline void Swap(StartVideoResponse* other) { + inline void Swap(SubscribeResetSettingsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3293,7 +3171,7 @@ class StartVideoResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StartVideoResponse* other) { + void UnsafeArenaSwap(SubscribeResetSettingsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3301,74 +3179,39 @@ class StartVideoResponse final : // implements Message ---------------------------------------------- - StartVideoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeResetSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StartVideoResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StartVideoResponse& from) { - StartVideoResponse::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeResetSettingsRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeResetSettingsRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StartVideoResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StartVideoResponse"; + return "mavsdk.rpc.camera_server.SubscribeResetSettingsRequest"; } protected: - explicit StartVideoResponse(::google::protobuf::Arena* arena); - StartVideoResponse(::google::protobuf::Arena* arena, const StartVideoResponse& from); + explicit SubscribeResetSettingsRequest(::google::protobuf::Arena* arena); + SubscribeResetSettingsRequest(::google::protobuf::Arena* arena, const SubscribeResetSettingsRequest& 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 { - kStreamIdFieldNumber = 1, - }; - // 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: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, - 0, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -3383,34 +3226,30 @@ class StartVideoResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t stream_id_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SetModeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetModeResponse) */ { +class SubscribeFormatStorageRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) */ { public: - inline SetModeResponse() : SetModeResponse(nullptr) {} - ~SetModeResponse() override; + inline SubscribeFormatStorageRequest() : SubscribeFormatStorageRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SetModeResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeFormatStorageRequest(::google::protobuf::internal::ConstantInitialized); - inline SetModeResponse(const SetModeResponse& from) - : SetModeResponse(nullptr, from) {} - SetModeResponse(SetModeResponse&& from) noexcept - : SetModeResponse() { + inline SubscribeFormatStorageRequest(const SubscribeFormatStorageRequest& from) + : SubscribeFormatStorageRequest(nullptr, from) {} + SubscribeFormatStorageRequest(SubscribeFormatStorageRequest&& from) noexcept + : SubscribeFormatStorageRequest() { *this = ::std::move(from); } - inline SetModeResponse& operator=(const SetModeResponse& from) { + inline SubscribeFormatStorageRequest& operator=(const SubscribeFormatStorageRequest& from) { CopyFrom(from); return *this; } - inline SetModeResponse& operator=(SetModeResponse&& from) noexcept { + inline SubscribeFormatStorageRequest& operator=(SubscribeFormatStorageRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3442,20 +3281,20 @@ class SetModeResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetModeResponse& default_instance() { + static const SubscribeFormatStorageRequest& default_instance() { return *internal_default_instance(); } - static inline const SetModeResponse* internal_default_instance() { - return reinterpret_cast( - &_SetModeResponse_default_instance_); + static inline const SubscribeFormatStorageRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeFormatStorageRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 27; + 38; - friend void swap(SetModeResponse& a, SetModeResponse& b) { + friend void swap(SubscribeFormatStorageRequest& a, SubscribeFormatStorageRequest& b) { a.Swap(&b); } - inline void Swap(SetModeResponse* other) { + inline void Swap(SubscribeFormatStorageRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3468,7 +3307,7 @@ class SetModeResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetModeResponse* other) { + void UnsafeArenaSwap(SubscribeFormatStorageRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3476,74 +3315,39 @@ class SetModeResponse final : // implements Message ---------------------------------------------- - SetModeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeFormatStorageRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetModeResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetModeResponse& from) { - SetModeResponse::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeFormatStorageRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeFormatStorageRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(SetModeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetModeResponse"; + return "mavsdk.rpc.camera_server.SubscribeFormatStorageRequest"; } protected: - explicit SetModeResponse(::google::protobuf::Arena* arena); - SetModeResponse(::google::protobuf::Arena* arena, const SetModeResponse& from); + explicit SubscribeFormatStorageRequest(::google::protobuf::Arena* arena); + SubscribeFormatStorageRequest(::google::protobuf::Arena* arena, const SubscribeFormatStorageRequest& 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 { - kModeFieldNumber = 1, - }; - // .mavsdk.rpc.camera_server.Mode mode = 1; - void clear_mode() ; - ::mavsdk::rpc::camera_server::Mode mode() const; - void set_mode(::mavsdk::rpc::camera_server::Mode value); - - private: - ::mavsdk::rpc::camera_server::Mode _internal_mode() const; - void _internal_set_mode(::mavsdk::rpc::camera_server::Mode value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetModeResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, - 0, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -3558,34 +3362,30 @@ class SetModeResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int mode_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SetInProgressRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInProgressRequest) */ { +class SubscribeCaptureStatusRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) */ { public: - inline SetInProgressRequest() : SetInProgressRequest(nullptr) {} - ~SetInProgressRequest() override; + inline SubscribeCaptureStatusRequest() : SubscribeCaptureStatusRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SetInProgressRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeCaptureStatusRequest(::google::protobuf::internal::ConstantInitialized); - inline SetInProgressRequest(const SetInProgressRequest& from) - : SetInProgressRequest(nullptr, from) {} - SetInProgressRequest(SetInProgressRequest&& from) noexcept - : SetInProgressRequest() { + inline SubscribeCaptureStatusRequest(const SubscribeCaptureStatusRequest& from) + : SubscribeCaptureStatusRequest(nullptr, from) {} + SubscribeCaptureStatusRequest(SubscribeCaptureStatusRequest&& from) noexcept + : SubscribeCaptureStatusRequest() { *this = ::std::move(from); } - inline SetInProgressRequest& operator=(const SetInProgressRequest& from) { + inline SubscribeCaptureStatusRequest& operator=(const SubscribeCaptureStatusRequest& from) { CopyFrom(from); return *this; } - inline SetInProgressRequest& operator=(SetInProgressRequest&& from) noexcept { + inline SubscribeCaptureStatusRequest& operator=(SubscribeCaptureStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3617,20 +3417,20 @@ class SetInProgressRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetInProgressRequest& default_instance() { + static const SubscribeCaptureStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const SetInProgressRequest* internal_default_instance() { - return reinterpret_cast( - &_SetInProgressRequest_default_instance_); + static inline const SubscribeCaptureStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeCaptureStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 4; + 34; - friend void swap(SetInProgressRequest& a, SetInProgressRequest& b) { + friend void swap(SubscribeCaptureStatusRequest& a, SubscribeCaptureStatusRequest& b) { a.Swap(&b); } - inline void Swap(SetInProgressRequest* other) { + inline void Swap(SubscribeCaptureStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3643,7 +3443,7 @@ class SetInProgressRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetInProgressRequest* other) { + void UnsafeArenaSwap(SubscribeCaptureStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3651,74 +3451,39 @@ class SetInProgressRequest final : // implements Message ---------------------------------------------- - SetInProgressRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeCaptureStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetInProgressRequest& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetInProgressRequest& from) { - SetInProgressRequest::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeCaptureStatusRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeCaptureStatusRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(SetInProgressRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetInProgressRequest"; + return "mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest"; } protected: - explicit SetInProgressRequest(::google::protobuf::Arena* arena); - SetInProgressRequest(::google::protobuf::Arena* arena, const SetInProgressRequest& from); + explicit SubscribeCaptureStatusRequest(::google::protobuf::Arena* arena); + SubscribeCaptureStatusRequest(::google::protobuf::Arena* arena, const SubscribeCaptureStatusRequest& 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 { - kInProgressFieldNumber = 1, - }; - // bool in_progress = 1; - void clear_in_progress() ; - bool in_progress() const; - void set_in_progress(bool value); - - private: - bool _internal_in_progress() const; - void _internal_set_in_progress(bool value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInProgressRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, - 0, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -3733,34 +3498,31 @@ class SetInProgressRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - bool in_progress_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStopVideoStreamingRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) */ { +class StorageInformationResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformationResponse) */ { public: - inline RespondStopVideoStreamingRequest() : RespondStopVideoStreamingRequest(nullptr) {} - ~RespondStopVideoStreamingRequest() override; + inline StorageInformationResponse() : StorageInformationResponse(nullptr) {} + ~StorageInformationResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondStopVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StorageInformationResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondStopVideoStreamingRequest(const RespondStopVideoStreamingRequest& from) - : RespondStopVideoStreamingRequest(nullptr, from) {} - RespondStopVideoStreamingRequest(RespondStopVideoStreamingRequest&& from) noexcept - : RespondStopVideoStreamingRequest() { + inline StorageInformationResponse(const StorageInformationResponse& from) + : StorageInformationResponse(nullptr, from) {} + StorageInformationResponse(StorageInformationResponse&& from) noexcept + : StorageInformationResponse() { *this = ::std::move(from); } - inline RespondStopVideoStreamingRequest& operator=(const RespondStopVideoStreamingRequest& from) { + inline StorageInformationResponse& operator=(const StorageInformationResponse& from) { CopyFrom(from); return *this; } - inline RespondStopVideoStreamingRequest& operator=(RespondStopVideoStreamingRequest&& from) noexcept { + inline StorageInformationResponse& operator=(StorageInformationResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3792,20 +3554,20 @@ class RespondStopVideoStreamingRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStopVideoStreamingRequest& default_instance() { + static const StorageInformationResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondStopVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondStopVideoStreamingRequest_default_instance_); + static inline const StorageInformationResponse* internal_default_instance() { + return reinterpret_cast( + &_StorageInformationResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 24; + 31; - friend void swap(RespondStopVideoStreamingRequest& a, RespondStopVideoStreamingRequest& b) { + friend void swap(StorageInformationResponse& a, StorageInformationResponse& b) { a.Swap(&b); } - inline void Swap(RespondStopVideoStreamingRequest* other) { + inline void Swap(StorageInformationResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3818,7 +3580,7 @@ class RespondStopVideoStreamingRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStopVideoStreamingRequest* other) { + void UnsafeArenaSwap(StorageInformationResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3826,14 +3588,14 @@ class RespondStopVideoStreamingRequest final : // implements Message ---------------------------------------------- - RespondStopVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StorageInformationResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStopVideoStreamingRequest& from); + void CopyFrom(const StorageInformationResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStopVideoStreamingRequest& from) { - RespondStopVideoStreamingRequest::MergeImpl(*this, from); + void MergeFrom( const StorageInformationResponse& from) { + StorageInformationResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -3851,16 +3613,16 @@ class RespondStopVideoStreamingRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStopVideoStreamingRequest* other); + void InternalSwap(StorageInformationResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest"; + return "mavsdk.rpc.camera_server.StorageInformationResponse"; } protected: - explicit RespondStopVideoStreamingRequest(::google::protobuf::Arena* arena); - RespondStopVideoStreamingRequest(::google::protobuf::Arena* arena, const RespondStopVideoStreamingRequest& from); + explicit StorageInformationResponse(::google::protobuf::Arena* arena); + StorageInformationResponse(::google::protobuf::Arena* arena, const StorageInformationResponse& from); public: static const ClassData _class_data_; @@ -3873,19 +3635,19 @@ class RespondStopVideoStreamingRequest final : // accessors ------------------------------------------------------- enum : int { - kStopVideoStreamingFeedbackFieldNumber = 1, + kStorageIdFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; - void clear_stop_video_streaming_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback stop_video_streaming_feedback() const; - void set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // int32 storage_id = 1; + void clear_storage_id() ; + ::int32_t storage_id() const; + void set_storage_id(::int32_t value); private: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_stop_video_streaming_feedback() const; - void _internal_set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + ::int32_t _internal_storage_id() const; + void _internal_set_storage_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformationResponse) private: class _Internal; @@ -3908,7 +3670,7 @@ class RespondStopVideoStreamingRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int stop_video_streaming_feedback_; + ::int32_t storage_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -3916,26 +3678,26 @@ class RespondStopVideoStreamingRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStopVideoRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoRequest) */ { +class StorageInformation final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformation) */ { public: - inline RespondStopVideoRequest() : RespondStopVideoRequest(nullptr) {} - ~RespondStopVideoRequest() override; + inline StorageInformation() : StorageInformation(nullptr) {} + ~StorageInformation() override; template - explicit PROTOBUF_CONSTEXPR RespondStopVideoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StorageInformation(::google::protobuf::internal::ConstantInitialized); - inline RespondStopVideoRequest(const RespondStopVideoRequest& from) - : RespondStopVideoRequest(nullptr, from) {} - RespondStopVideoRequest(RespondStopVideoRequest&& from) noexcept - : RespondStopVideoRequest() { + inline StorageInformation(const StorageInformation& from) + : StorageInformation(nullptr, from) {} + StorageInformation(StorageInformation&& from) noexcept + : StorageInformation() { *this = ::std::move(from); } - inline RespondStopVideoRequest& operator=(const RespondStopVideoRequest& from) { + inline StorageInformation& operator=(const StorageInformation& from) { CopyFrom(from); return *this; } - inline RespondStopVideoRequest& operator=(RespondStopVideoRequest&& from) noexcept { + inline StorageInformation& operator=(StorageInformation&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3967,20 +3729,20 @@ class RespondStopVideoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStopVideoRequest& default_instance() { + static const StorageInformation& default_instance() { return *internal_default_instance(); } - static inline const RespondStopVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondStopVideoRequest_default_instance_); + static inline const StorageInformation* internal_default_instance() { + return reinterpret_cast( + &_StorageInformation_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 68; - friend void swap(RespondStopVideoRequest& a, RespondStopVideoRequest& b) { + friend void swap(StorageInformation& a, StorageInformation& b) { a.Swap(&b); } - inline void Swap(RespondStopVideoRequest* other) { + inline void Swap(StorageInformation* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3993,7 +3755,7 @@ class RespondStopVideoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStopVideoRequest* other) { + void UnsafeArenaSwap(StorageInformation* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4001,14 +3763,14 @@ class RespondStopVideoRequest final : // implements Message ---------------------------------------------- - RespondStopVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StorageInformation* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStopVideoRequest& from); + void CopyFrom(const StorageInformation& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStopVideoRequest& from) { - RespondStopVideoRequest::MergeImpl(*this, from); + void MergeFrom( const StorageInformation& from) { + StorageInformation::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4026,16 +3788,16 @@ class RespondStopVideoRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStopVideoRequest* other); + void InternalSwap(StorageInformation* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStopVideoRequest"; + return "mavsdk.rpc.camera_server.StorageInformation"; } protected: - explicit RespondStopVideoRequest(::google::protobuf::Arena* arena); - RespondStopVideoRequest(::google::protobuf::Arena* arena, const RespondStopVideoRequest& from); + explicit StorageInformation(::google::protobuf::Arena* arena); + StorageInformation(::google::protobuf::Arena* arena, const StorageInformation& from); public: static const ClassData _class_data_; @@ -4045,37 +3807,160 @@ class RespondStopVideoRequest final : // nested types ---------------------------------------------------- - // accessors ------------------------------------------------------- - - enum : int { - kStopVideoFeedbackFieldNumber = 1, - }; - // .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; - void clear_stop_video_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback stop_video_feedback() const; - void set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); - - private: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_stop_video_feedback() const; - void _internal_set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoRequest) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; + using StorageStatus = StorageInformation_StorageStatus; + static constexpr StorageStatus STORAGE_STATUS_NOT_AVAILABLE = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE; + static constexpr StorageStatus STORAGE_STATUS_UNFORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_UNFORMATTED; + static constexpr StorageStatus STORAGE_STATUS_FORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_FORMATTED; + static constexpr StorageStatus STORAGE_STATUS_NOT_SUPPORTED = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED; + static inline bool StorageStatus_IsValid(int value) { + return StorageInformation_StorageStatus_IsValid(value); + } + static constexpr StorageStatus StorageStatus_MIN = StorageInformation_StorageStatus_StorageStatus_MIN; + static constexpr StorageStatus StorageStatus_MAX = StorageInformation_StorageStatus_StorageStatus_MAX; + static constexpr int StorageStatus_ARRAYSIZE = StorageInformation_StorageStatus_StorageStatus_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* StorageStatus_descriptor() { + return StorageInformation_StorageStatus_descriptor(); + } template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { + static inline const std::string& StorageStatus_Name(T value) { + return StorageInformation_StorageStatus_Name(value); + } + static inline bool StorageStatus_Parse(absl::string_view name, StorageStatus* value) { + return StorageInformation_StorageStatus_Parse(name, value); + } + + using StorageType = StorageInformation_StorageType; + static constexpr StorageType STORAGE_TYPE_UNKNOWN = StorageInformation_StorageType_STORAGE_TYPE_UNKNOWN; + static constexpr StorageType STORAGE_TYPE_USB_STICK = StorageInformation_StorageType_STORAGE_TYPE_USB_STICK; + static constexpr StorageType STORAGE_TYPE_SD = StorageInformation_StorageType_STORAGE_TYPE_SD; + static constexpr StorageType STORAGE_TYPE_MICROSD = StorageInformation_StorageType_STORAGE_TYPE_MICROSD; + static constexpr StorageType STORAGE_TYPE_HD = StorageInformation_StorageType_STORAGE_TYPE_HD; + static constexpr StorageType STORAGE_TYPE_OTHER = StorageInformation_StorageType_STORAGE_TYPE_OTHER; + static inline bool StorageType_IsValid(int value) { + return StorageInformation_StorageType_IsValid(value); + } + static constexpr StorageType StorageType_MIN = StorageInformation_StorageType_StorageType_MIN; + static constexpr StorageType StorageType_MAX = StorageInformation_StorageType_StorageType_MAX; + static constexpr int StorageType_ARRAYSIZE = StorageInformation_StorageType_StorageType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* StorageType_descriptor() { + return StorageInformation_StorageType_descriptor(); + } + template + static inline const std::string& StorageType_Name(T value) { + return StorageInformation_StorageType_Name(value); + } + static inline bool StorageType_Parse(absl::string_view name, StorageType* value) { + return StorageInformation_StorageType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + enum : int { + kUsedStorageMibFieldNumber = 1, + kAvailableStorageMibFieldNumber = 2, + kTotalStorageMibFieldNumber = 3, + kStorageStatusFieldNumber = 4, + kStorageIdFieldNumber = 5, + kStorageTypeFieldNumber = 6, + kReadSpeedMibSFieldNumber = 7, + kWriteSpeedMibSFieldNumber = 8, + }; + // float used_storage_mib = 1; + void clear_used_storage_mib() ; + float used_storage_mib() const; + void set_used_storage_mib(float value); + + private: + float _internal_used_storage_mib() const; + void _internal_set_used_storage_mib(float value); + + public: + // float available_storage_mib = 2; + void clear_available_storage_mib() ; + float available_storage_mib() const; + void set_available_storage_mib(float value); + + private: + float _internal_available_storage_mib() const; + void _internal_set_available_storage_mib(float value); + + public: + // float total_storage_mib = 3; + void clear_total_storage_mib() ; + float total_storage_mib() const; + void set_total_storage_mib(float value); + + private: + float _internal_total_storage_mib() const; + void _internal_set_total_storage_mib(float value); + + public: + // .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; + void clear_storage_status() ; + ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus storage_status() const; + void set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); + + private: + ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus _internal_storage_status() const; + void _internal_set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); + + public: + // uint32 storage_id = 5; + void clear_storage_id() ; + ::uint32_t storage_id() const; + void set_storage_id(::uint32_t value); + + private: + ::uint32_t _internal_storage_id() const; + void _internal_set_storage_id(::uint32_t value); + + public: + // .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; + void clear_storage_type() ; + ::mavsdk::rpc::camera_server::StorageInformation_StorageType storage_type() const; + void set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); + + private: + ::mavsdk::rpc::camera_server::StorageInformation_StorageType _internal_storage_type() const; + void _internal_set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); + + public: + // float read_speed_mib_s = 7; + void clear_read_speed_mib_s() ; + float read_speed_mib_s() const; + void set_read_speed_mib_s(float value); + + private: + float _internal_read_speed_mib_s() const; + void _internal_set_read_speed_mib_s(float value); + + public: + // float write_speed_mib_s = 8; + void clear_write_speed_mib_s() ; + float write_speed_mib_s() const; + void set_write_speed_mib_s(float value); + + private: + float _internal_write_speed_mib_s() const; + void _internal_set_write_speed_mib_s(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformation) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 3, 8, 0, + 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; @@ -4083,7 +3968,14 @@ class RespondStopVideoRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int stop_video_feedback_; + float used_storage_mib_; + float available_storage_mib_; + float total_storage_mib_; + int storage_status_; + ::uint32_t storage_id_; + int storage_type_; + float read_speed_mib_s_; + float write_speed_mib_s_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -4091,26 +3983,26 @@ class RespondStopVideoRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStartVideoStreamingRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) */ { +class StopVideoStreamingResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoStreamingResponse) */ { public: - inline RespondStartVideoStreamingRequest() : RespondStartVideoStreamingRequest(nullptr) {} - ~RespondStartVideoStreamingRequest() override; + inline StopVideoStreamingResponse() : StopVideoStreamingResponse(nullptr) {} + ~StopVideoStreamingResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondStartVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StopVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondStartVideoStreamingRequest(const RespondStartVideoStreamingRequest& from) - : RespondStartVideoStreamingRequest(nullptr, from) {} - RespondStartVideoStreamingRequest(RespondStartVideoStreamingRequest&& from) noexcept - : RespondStartVideoStreamingRequest() { + inline StopVideoStreamingResponse(const StopVideoStreamingResponse& from) + : StopVideoStreamingResponse(nullptr, from) {} + StopVideoStreamingResponse(StopVideoStreamingResponse&& from) noexcept + : StopVideoStreamingResponse() { *this = ::std::move(from); } - inline RespondStartVideoStreamingRequest& operator=(const RespondStartVideoStreamingRequest& from) { + inline StopVideoStreamingResponse& operator=(const StopVideoStreamingResponse& from) { CopyFrom(from); return *this; } - inline RespondStartVideoStreamingRequest& operator=(RespondStartVideoStreamingRequest&& from) noexcept { + inline StopVideoStreamingResponse& operator=(StopVideoStreamingResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4142,20 +4034,20 @@ class RespondStartVideoStreamingRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStartVideoStreamingRequest& default_instance() { + static const StopVideoStreamingResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondStartVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondStartVideoStreamingRequest_default_instance_); + static inline const StopVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_StopVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 23; - friend void swap(RespondStartVideoStreamingRequest& a, RespondStartVideoStreamingRequest& b) { + friend void swap(StopVideoStreamingResponse& a, StopVideoStreamingResponse& b) { a.Swap(&b); } - inline void Swap(RespondStartVideoStreamingRequest* other) { + inline void Swap(StopVideoStreamingResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4168,7 +4060,7 @@ class RespondStartVideoStreamingRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStartVideoStreamingRequest* other) { + void UnsafeArenaSwap(StopVideoStreamingResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4176,14 +4068,14 @@ class RespondStartVideoStreamingRequest final : // implements Message ---------------------------------------------- - RespondStartVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StopVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStartVideoStreamingRequest& from); + void CopyFrom(const StopVideoStreamingResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStartVideoStreamingRequest& from) { - RespondStartVideoStreamingRequest::MergeImpl(*this, from); + void MergeFrom( const StopVideoStreamingResponse& from) { + StopVideoStreamingResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4201,16 +4093,16 @@ class RespondStartVideoStreamingRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStartVideoStreamingRequest* other); + void InternalSwap(StopVideoStreamingResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest"; + return "mavsdk.rpc.camera_server.StopVideoStreamingResponse"; } protected: - explicit RespondStartVideoStreamingRequest(::google::protobuf::Arena* arena); - RespondStartVideoStreamingRequest(::google::protobuf::Arena* arena, const RespondStartVideoStreamingRequest& from); + explicit StopVideoStreamingResponse(::google::protobuf::Arena* arena); + StopVideoStreamingResponse(::google::protobuf::Arena* arena, const StopVideoStreamingResponse& from); public: static const ClassData _class_data_; @@ -4223,19 +4115,19 @@ class RespondStartVideoStreamingRequest final : // accessors ------------------------------------------------------- enum : int { - kStartVideoStreamingFeedbackFieldNumber = 1, + kStreamIdFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; - void clear_start_video_streaming_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback start_video_streaming_feedback() const; - void set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); private: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_start_video_streaming_feedback() const; - void _internal_set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoStreamingResponse) private: class _Internal; @@ -4258,7 +4150,7 @@ class RespondStartVideoStreamingRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int start_video_streaming_feedback_; + ::int32_t stream_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -4266,26 +4158,26 @@ class RespondStartVideoStreamingRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStartVideoRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoRequest) */ { +class StopVideoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoResponse) */ { public: - inline RespondStartVideoRequest() : RespondStartVideoRequest(nullptr) {} - ~RespondStartVideoRequest() override; + inline StopVideoResponse() : StopVideoResponse(nullptr) {} + ~StopVideoResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondStartVideoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StopVideoResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondStartVideoRequest(const RespondStartVideoRequest& from) - : RespondStartVideoRequest(nullptr, from) {} - RespondStartVideoRequest(RespondStartVideoRequest&& from) noexcept - : RespondStartVideoRequest() { + inline StopVideoResponse(const StopVideoResponse& from) + : StopVideoResponse(nullptr, from) {} + StopVideoResponse(StopVideoResponse&& from) noexcept + : StopVideoResponse() { *this = ::std::move(from); } - inline RespondStartVideoRequest& operator=(const RespondStartVideoRequest& from) { + inline StopVideoResponse& operator=(const StopVideoResponse& from) { CopyFrom(from); return *this; } - inline RespondStartVideoRequest& operator=(RespondStartVideoRequest&& from) noexcept { + inline StopVideoResponse& operator=(StopVideoResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4317,20 +4209,20 @@ class RespondStartVideoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStartVideoRequest& default_instance() { + static const StopVideoResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondStartVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondStartVideoRequest_default_instance_); + static inline const StopVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_StopVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 15; - friend void swap(RespondStartVideoRequest& a, RespondStartVideoRequest& b) { + friend void swap(StopVideoResponse& a, StopVideoResponse& b) { a.Swap(&b); } - inline void Swap(RespondStartVideoRequest* other) { + inline void Swap(StopVideoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4343,7 +4235,7 @@ class RespondStartVideoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStartVideoRequest* other) { + void UnsafeArenaSwap(StopVideoResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4351,14 +4243,14 @@ class RespondStartVideoRequest final : // implements Message ---------------------------------------------- - RespondStartVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StopVideoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStartVideoRequest& from); + void CopyFrom(const StopVideoResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStartVideoRequest& from) { - RespondStartVideoRequest::MergeImpl(*this, from); + void MergeFrom( const StopVideoResponse& from) { + StopVideoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4376,16 +4268,16 @@ class RespondStartVideoRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStartVideoRequest* other); + void InternalSwap(StopVideoResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStartVideoRequest"; + return "mavsdk.rpc.camera_server.StopVideoResponse"; } protected: - explicit RespondStartVideoRequest(::google::protobuf::Arena* arena); - RespondStartVideoRequest(::google::protobuf::Arena* arena, const RespondStartVideoRequest& from); + explicit StopVideoResponse(::google::protobuf::Arena* arena); + StopVideoResponse(::google::protobuf::Arena* arena, const StopVideoResponse& from); public: static const ClassData _class_data_; @@ -4398,19 +4290,19 @@ class RespondStartVideoRequest final : // accessors ------------------------------------------------------- enum : int { - kStartVideoFeedbackFieldNumber = 1, + kStreamIdFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraFeedback start_video_feedback = 1; - void clear_start_video_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback start_video_feedback() const; - void set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); private: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_start_video_feedback() const; - void _internal_set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoResponse) private: class _Internal; @@ -4433,7 +4325,7 @@ class RespondStartVideoRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int start_video_feedback_; + ::int32_t stream_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -4441,26 +4333,26 @@ class RespondStartVideoRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondSetModeRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondSetModeRequest) */ { +class StartVideoStreamingResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoStreamingResponse) */ { public: - inline RespondSetModeRequest() : RespondSetModeRequest(nullptr) {} - ~RespondSetModeRequest() override; + inline StartVideoStreamingResponse() : StartVideoStreamingResponse(nullptr) {} + ~StartVideoStreamingResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondSetModeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StartVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondSetModeRequest(const RespondSetModeRequest& from) - : RespondSetModeRequest(nullptr, from) {} - RespondSetModeRequest(RespondSetModeRequest&& from) noexcept - : RespondSetModeRequest() { + inline StartVideoStreamingResponse(const StartVideoStreamingResponse& from) + : StartVideoStreamingResponse(nullptr, from) {} + StartVideoStreamingResponse(StartVideoStreamingResponse&& from) noexcept + : StartVideoStreamingResponse() { *this = ::std::move(from); } - inline RespondSetModeRequest& operator=(const RespondSetModeRequest& from) { + inline StartVideoStreamingResponse& operator=(const StartVideoStreamingResponse& from) { CopyFrom(from); return *this; } - inline RespondSetModeRequest& operator=(RespondSetModeRequest&& from) noexcept { + inline StartVideoStreamingResponse& operator=(StartVideoStreamingResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4492,20 +4384,20 @@ class RespondSetModeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondSetModeRequest& default_instance() { + static const StartVideoStreamingResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondSetModeRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondSetModeRequest_default_instance_); + static inline const StartVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_StartVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 28; + 19; - friend void swap(RespondSetModeRequest& a, RespondSetModeRequest& b) { + friend void swap(StartVideoStreamingResponse& a, StartVideoStreamingResponse& b) { a.Swap(&b); } - inline void Swap(RespondSetModeRequest* other) { + inline void Swap(StartVideoStreamingResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4518,7 +4410,7 @@ class RespondSetModeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondSetModeRequest* other) { + void UnsafeArenaSwap(StartVideoStreamingResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4526,14 +4418,14 @@ class RespondSetModeRequest final : // implements Message ---------------------------------------------- - RespondSetModeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StartVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondSetModeRequest& from); + void CopyFrom(const StartVideoStreamingResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondSetModeRequest& from) { - RespondSetModeRequest::MergeImpl(*this, from); + void MergeFrom( const StartVideoStreamingResponse& from) { + StartVideoStreamingResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4551,16 +4443,16 @@ class RespondSetModeRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondSetModeRequest* other); + void InternalSwap(StartVideoStreamingResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondSetModeRequest"; + return "mavsdk.rpc.camera_server.StartVideoStreamingResponse"; } protected: - explicit RespondSetModeRequest(::google::protobuf::Arena* arena); - RespondSetModeRequest(::google::protobuf::Arena* arena, const RespondSetModeRequest& from); + explicit StartVideoStreamingResponse(::google::protobuf::Arena* arena); + StartVideoStreamingResponse(::google::protobuf::Arena* arena, const StartVideoStreamingResponse& from); public: static const ClassData _class_data_; @@ -4573,19 +4465,19 @@ class RespondSetModeRequest final : // accessors ------------------------------------------------------- enum : int { - kSetModeFeedbackFieldNumber = 1, + kStreamIdFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraFeedback set_mode_feedback = 1; - void clear_set_mode_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback set_mode_feedback() const; - void set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); private: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_set_mode_feedback() const; - void _internal_set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondSetModeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoStreamingResponse) private: class _Internal; @@ -4608,7 +4500,7 @@ class RespondSetModeRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int set_mode_feedback_; + ::int32_t stream_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -4616,26 +4508,26 @@ class RespondSetModeRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondResetSettingsRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondResetSettingsRequest) */ { +class StartVideoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoResponse) */ { public: - inline RespondResetSettingsRequest() : RespondResetSettingsRequest(nullptr) {} - ~RespondResetSettingsRequest() override; + inline StartVideoResponse() : StartVideoResponse(nullptr) {} + ~StartVideoResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondResetSettingsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StartVideoResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondResetSettingsRequest(const RespondResetSettingsRequest& from) - : RespondResetSettingsRequest(nullptr, from) {} - RespondResetSettingsRequest(RespondResetSettingsRequest&& from) noexcept - : RespondResetSettingsRequest() { + inline StartVideoResponse(const StartVideoResponse& from) + : StartVideoResponse(nullptr, from) {} + StartVideoResponse(StartVideoResponse&& from) noexcept + : StartVideoResponse() { *this = ::std::move(from); } - inline RespondResetSettingsRequest& operator=(const RespondResetSettingsRequest& from) { + inline StartVideoResponse& operator=(const StartVideoResponse& from) { CopyFrom(from); return *this; } - inline RespondResetSettingsRequest& operator=(RespondResetSettingsRequest&& from) noexcept { + inline StartVideoResponse& operator=(StartVideoResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4667,20 +4559,20 @@ class RespondResetSettingsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondResetSettingsRequest& default_instance() { + static const StartVideoResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondResetSettingsRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondResetSettingsRequest_default_instance_); + static inline const StartVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_StartVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 44; + 11; - friend void swap(RespondResetSettingsRequest& a, RespondResetSettingsRequest& b) { + friend void swap(StartVideoResponse& a, StartVideoResponse& b) { a.Swap(&b); } - inline void Swap(RespondResetSettingsRequest* other) { + inline void Swap(StartVideoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4693,7 +4585,7 @@ class RespondResetSettingsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondResetSettingsRequest* other) { + void UnsafeArenaSwap(StartVideoResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4701,14 +4593,14 @@ class RespondResetSettingsRequest final : // implements Message ---------------------------------------------- - RespondResetSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StartVideoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondResetSettingsRequest& from); + void CopyFrom(const StartVideoResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondResetSettingsRequest& from) { - RespondResetSettingsRequest::MergeImpl(*this, from); + void MergeFrom( const StartVideoResponse& from) { + StartVideoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4726,16 +4618,16 @@ class RespondResetSettingsRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondResetSettingsRequest* other); + void InternalSwap(StartVideoResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondResetSettingsRequest"; + return "mavsdk.rpc.camera_server.StartVideoResponse"; } protected: - explicit RespondResetSettingsRequest(::google::protobuf::Arena* arena); - RespondResetSettingsRequest(::google::protobuf::Arena* arena, const RespondResetSettingsRequest& from); + explicit StartVideoResponse(::google::protobuf::Arena* arena); + StartVideoResponse(::google::protobuf::Arena* arena, const StartVideoResponse& from); public: static const ClassData _class_data_; @@ -4748,19 +4640,19 @@ class RespondResetSettingsRequest final : // accessors ------------------------------------------------------- enum : int { - kResetSettingsFeedbackFieldNumber = 1, + kStreamIdFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; - void clear_reset_settings_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback reset_settings_feedback() const; - void set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); private: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_reset_settings_feedback() const; - void _internal_set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoResponse) private: class _Internal; @@ -4783,7 +4675,7 @@ class RespondResetSettingsRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int reset_settings_feedback_; + ::int32_t stream_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -4791,26 +4683,26 @@ class RespondResetSettingsRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondFormatStorageRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondFormatStorageRequest) */ { +class SetModeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetModeResponse) */ { public: - inline RespondFormatStorageRequest() : RespondFormatStorageRequest(nullptr) {} - ~RespondFormatStorageRequest() override; + inline SetModeResponse() : SetModeResponse(nullptr) {} + ~SetModeResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondFormatStorageRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetModeResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondFormatStorageRequest(const RespondFormatStorageRequest& from) - : RespondFormatStorageRequest(nullptr, from) {} - RespondFormatStorageRequest(RespondFormatStorageRequest&& from) noexcept - : RespondFormatStorageRequest() { + inline SetModeResponse(const SetModeResponse& from) + : SetModeResponse(nullptr, from) {} + SetModeResponse(SetModeResponse&& from) noexcept + : SetModeResponse() { *this = ::std::move(from); } - inline RespondFormatStorageRequest& operator=(const RespondFormatStorageRequest& from) { + inline SetModeResponse& operator=(const SetModeResponse& from) { CopyFrom(from); return *this; } - inline RespondFormatStorageRequest& operator=(RespondFormatStorageRequest&& from) noexcept { + inline SetModeResponse& operator=(SetModeResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4842,20 +4734,20 @@ class RespondFormatStorageRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondFormatStorageRequest& default_instance() { + static const SetModeResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondFormatStorageRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondFormatStorageRequest_default_instance_); + static inline const SetModeResponse* internal_default_instance() { + return reinterpret_cast( + &_SetModeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 40; + 27; - friend void swap(RespondFormatStorageRequest& a, RespondFormatStorageRequest& b) { + friend void swap(SetModeResponse& a, SetModeResponse& b) { a.Swap(&b); } - inline void Swap(RespondFormatStorageRequest* other) { + inline void Swap(SetModeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4868,7 +4760,7 @@ class RespondFormatStorageRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondFormatStorageRequest* other) { + void UnsafeArenaSwap(SetModeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4876,14 +4768,14 @@ class RespondFormatStorageRequest final : // implements Message ---------------------------------------------- - RespondFormatStorageRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetModeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondFormatStorageRequest& from); + void CopyFrom(const SetModeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondFormatStorageRequest& from) { - RespondFormatStorageRequest::MergeImpl(*this, from); + void MergeFrom( const SetModeResponse& from) { + SetModeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4901,16 +4793,16 @@ class RespondFormatStorageRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondFormatStorageRequest* other); + void InternalSwap(SetModeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondFormatStorageRequest"; + return "mavsdk.rpc.camera_server.SetModeResponse"; } protected: - explicit RespondFormatStorageRequest(::google::protobuf::Arena* arena); - RespondFormatStorageRequest(::google::protobuf::Arena* arena, const RespondFormatStorageRequest& from); + explicit SetModeResponse(::google::protobuf::Arena* arena); + SetModeResponse(::google::protobuf::Arena* arena, const SetModeResponse& from); public: static const ClassData _class_data_; @@ -4923,19 +4815,19 @@ class RespondFormatStorageRequest final : // accessors ------------------------------------------------------- enum : int { - kFormatStorageFeedbackFieldNumber = 1, + kModeFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; - void clear_format_storage_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback format_storage_feedback() const; - void set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // .mavsdk.rpc.camera_server.Mode mode = 1; + void clear_mode() ; + ::mavsdk::rpc::camera_server::Mode mode() const; + void set_mode(::mavsdk::rpc::camera_server::Mode value); private: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_format_storage_feedback() const; - void _internal_set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + ::mavsdk::rpc::camera_server::Mode _internal_mode() const; + void _internal_set_mode(::mavsdk::rpc::camera_server::Mode value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondFormatStorageRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetModeResponse) private: class _Internal; @@ -4958,7 +4850,7 @@ class RespondFormatStorageRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int format_storage_feedback_; + int mode_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -4966,26 +4858,26 @@ class RespondFormatStorageRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class ResetSettingsResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ResetSettingsResponse) */ { +class SetInProgressRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInProgressRequest) */ { public: - inline ResetSettingsResponse() : ResetSettingsResponse(nullptr) {} - ~ResetSettingsResponse() override; + inline SetInProgressRequest() : SetInProgressRequest(nullptr) {} + ~SetInProgressRequest() override; template - explicit PROTOBUF_CONSTEXPR ResetSettingsResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetInProgressRequest(::google::protobuf::internal::ConstantInitialized); - inline ResetSettingsResponse(const ResetSettingsResponse& from) - : ResetSettingsResponse(nullptr, from) {} - ResetSettingsResponse(ResetSettingsResponse&& from) noexcept - : ResetSettingsResponse() { + inline SetInProgressRequest(const SetInProgressRequest& from) + : SetInProgressRequest(nullptr, from) {} + SetInProgressRequest(SetInProgressRequest&& from) noexcept + : SetInProgressRequest() { *this = ::std::move(from); } - inline ResetSettingsResponse& operator=(const ResetSettingsResponse& from) { + inline SetInProgressRequest& operator=(const SetInProgressRequest& from) { CopyFrom(from); return *this; } - inline ResetSettingsResponse& operator=(ResetSettingsResponse&& from) noexcept { + inline SetInProgressRequest& operator=(SetInProgressRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5017,20 +4909,20 @@ class ResetSettingsResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ResetSettingsResponse& default_instance() { + static const SetInProgressRequest& default_instance() { return *internal_default_instance(); } - static inline const ResetSettingsResponse* internal_default_instance() { - return reinterpret_cast( - &_ResetSettingsResponse_default_instance_); + static inline const SetInProgressRequest* internal_default_instance() { + return reinterpret_cast( + &_SetInProgressRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 43; + 4; - friend void swap(ResetSettingsResponse& a, ResetSettingsResponse& b) { + friend void swap(SetInProgressRequest& a, SetInProgressRequest& b) { a.Swap(&b); } - inline void Swap(ResetSettingsResponse* other) { + inline void Swap(SetInProgressRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5043,7 +4935,7 @@ class ResetSettingsResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ResetSettingsResponse* other) { + void UnsafeArenaSwap(SetInProgressRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5051,14 +4943,14 @@ class ResetSettingsResponse final : // implements Message ---------------------------------------------- - ResetSettingsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetInProgressRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ResetSettingsResponse& from); + void CopyFrom(const SetInProgressRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ResetSettingsResponse& from) { - ResetSettingsResponse::MergeImpl(*this, from); + void MergeFrom( const SetInProgressRequest& from) { + SetInProgressRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -5076,16 +4968,16 @@ class ResetSettingsResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(ResetSettingsResponse* other); + void InternalSwap(SetInProgressRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.ResetSettingsResponse"; + return "mavsdk.rpc.camera_server.SetInProgressRequest"; } protected: - explicit ResetSettingsResponse(::google::protobuf::Arena* arena); - ResetSettingsResponse(::google::protobuf::Arena* arena, const ResetSettingsResponse& from); + explicit SetInProgressRequest(::google::protobuf::Arena* arena); + SetInProgressRequest(::google::protobuf::Arena* arena, const SetInProgressRequest& from); public: static const ClassData _class_data_; @@ -5098,19 +4990,19 @@ class ResetSettingsResponse final : // accessors ------------------------------------------------------- enum : int { - kReservedFieldNumber = 1, + kInProgressFieldNumber = 1, }; - // int32 reserved = 1; - void clear_reserved() ; - ::int32_t reserved() const; - void set_reserved(::int32_t value); + // bool in_progress = 1; + void clear_in_progress() ; + bool in_progress() const; + void set_in_progress(bool value); private: - ::int32_t _internal_reserved() const; - void _internal_set_reserved(::int32_t value); + bool _internal_in_progress() const; + void _internal_set_in_progress(bool value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ResetSettingsResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInProgressRequest) private: class _Internal; @@ -5133,7 +5025,7 @@ class ResetSettingsResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t reserved_; + bool in_progress_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -5141,26 +5033,26 @@ class ResetSettingsResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Quaternion final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Quaternion) */ { +class RespondZoomStopRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondZoomStopRequest) */ { public: - inline Quaternion() : Quaternion(nullptr) {} - ~Quaternion() override; + inline RespondZoomStopRequest() : RespondZoomStopRequest(nullptr) {} + ~RespondZoomStopRequest() override; template - explicit PROTOBUF_CONSTEXPR Quaternion(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondZoomStopRequest(::google::protobuf::internal::ConstantInitialized); - inline Quaternion(const Quaternion& from) - : Quaternion(nullptr, from) {} - Quaternion(Quaternion&& from) noexcept - : Quaternion() { + inline RespondZoomStopRequest(const RespondZoomStopRequest& from) + : RespondZoomStopRequest(nullptr, from) {} + RespondZoomStopRequest(RespondZoomStopRequest&& from) noexcept + : RespondZoomStopRequest() { *this = ::std::move(from); } - inline Quaternion& operator=(const Quaternion& from) { + inline RespondZoomStopRequest& operator=(const RespondZoomStopRequest& from) { CopyFrom(from); return *this; } - inline Quaternion& operator=(Quaternion&& from) noexcept { + inline RespondZoomStopRequest& operator=(RespondZoomStopRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5192,20 +5084,20 @@ class Quaternion final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Quaternion& default_instance() { + static const RespondZoomStopRequest& default_instance() { return *internal_default_instance(); } - static inline const Quaternion* internal_default_instance() { - return reinterpret_cast( - &_Quaternion_default_instance_); + static inline const RespondZoomStopRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondZoomStopRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 49; + 56; - friend void swap(Quaternion& a, Quaternion& b) { + friend void swap(RespondZoomStopRequest& a, RespondZoomStopRequest& b) { a.Swap(&b); } - inline void Swap(Quaternion* other) { + inline void Swap(RespondZoomStopRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5218,7 +5110,7 @@ class Quaternion final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Quaternion* other) { + void UnsafeArenaSwap(RespondZoomStopRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5226,14 +5118,14 @@ class Quaternion final : // implements Message ---------------------------------------------- - Quaternion* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondZoomStopRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Quaternion& from); + void CopyFrom(const RespondZoomStopRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Quaternion& from) { - Quaternion::MergeImpl(*this, from); + void MergeFrom( const RespondZoomStopRequest& from) { + RespondZoomStopRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -5251,16 +5143,16 @@ class Quaternion final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Quaternion* other); + void InternalSwap(RespondZoomStopRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Quaternion"; + return "mavsdk.rpc.camera_server.RespondZoomStopRequest"; } protected: - explicit Quaternion(::google::protobuf::Arena* arena); - Quaternion(::google::protobuf::Arena* arena, const Quaternion& from); + explicit RespondZoomStopRequest(::google::protobuf::Arena* arena); + RespondZoomStopRequest(::google::protobuf::Arena* arena, const RespondZoomStopRequest& from); public: static const ClassData _class_data_; @@ -5273,58 +5165,25 @@ class Quaternion final : // accessors ------------------------------------------------------- enum : int { - kWFieldNumber = 1, - kXFieldNumber = 2, - kYFieldNumber = 3, - kZFieldNumber = 4, + kZoomStopFeedbackFieldNumber = 1, }; - // float w = 1; - void clear_w() ; - float w() const; - void set_w(float value); - - private: - float _internal_w() const; - void _internal_set_w(float value); - - public: - // float x = 2; - void clear_x() ; - float x() const; - void set_x(float value); - - private: - float _internal_x() const; - void _internal_set_x(float value); - - public: - // float y = 3; - void clear_y() ; - float y() const; - void set_y(float value); - - private: - float _internal_y() const; - void _internal_set_y(float value); - - public: - // float z = 4; - void clear_z() ; - float z() const; - void set_z(float value); + // .mavsdk.rpc.camera_server.CameraFeedback zoom_stop_feedback = 1; + void clear_zoom_stop_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback zoom_stop_feedback() const; + void set_zoom_stop_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - float _internal_z() const; - void _internal_set_z(float value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_zoom_stop_feedback() const; + void _internal_set_zoom_stop_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Quaternion) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondZoomStopRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 4, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -5341,10 +5200,7 @@ class Quaternion final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float w_; - float x_; - float y_; - float z_; + int zoom_stop_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -5352,26 +5208,26 @@ class Quaternion final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Position final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Position) */ { +class RespondZoomRangeRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondZoomRangeRequest) */ { public: - inline Position() : Position(nullptr) {} - ~Position() override; + inline RespondZoomRangeRequest() : RespondZoomRangeRequest(nullptr) {} + ~RespondZoomRangeRequest() override; template - explicit PROTOBUF_CONSTEXPR Position(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondZoomRangeRequest(::google::protobuf::internal::ConstantInitialized); - inline Position(const Position& from) - : Position(nullptr, from) {} - Position(Position&& from) noexcept - : Position() { + inline RespondZoomRangeRequest(const RespondZoomRangeRequest& from) + : RespondZoomRangeRequest(nullptr, from) {} + RespondZoomRangeRequest(RespondZoomRangeRequest&& from) noexcept + : RespondZoomRangeRequest() { *this = ::std::move(from); } - inline Position& operator=(const Position& from) { + inline RespondZoomRangeRequest& operator=(const RespondZoomRangeRequest& from) { CopyFrom(from); return *this; } - inline Position& operator=(Position&& from) noexcept { + inline RespondZoomRangeRequest& operator=(RespondZoomRangeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5403,20 +5259,20 @@ class Position final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Position& default_instance() { + static const RespondZoomRangeRequest& default_instance() { return *internal_default_instance(); } - static inline const Position* internal_default_instance() { - return reinterpret_cast( - &_Position_default_instance_); + static inline const RespondZoomRangeRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondZoomRangeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 48; + 60; - friend void swap(Position& a, Position& b) { + friend void swap(RespondZoomRangeRequest& a, RespondZoomRangeRequest& b) { a.Swap(&b); } - inline void Swap(Position* other) { + inline void Swap(RespondZoomRangeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5429,7 +5285,7 @@ class Position final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Position* other) { + void UnsafeArenaSwap(RespondZoomRangeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5437,14 +5293,14 @@ class Position final : // implements Message ---------------------------------------------- - Position* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondZoomRangeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Position& from); + void CopyFrom(const RespondZoomRangeRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Position& from) { - Position::MergeImpl(*this, from); + void MergeFrom( const RespondZoomRangeRequest& from) { + RespondZoomRangeRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -5462,16 +5318,16 @@ class Position final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Position* other); + void InternalSwap(RespondZoomRangeRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Position"; + return "mavsdk.rpc.camera_server.RespondZoomRangeRequest"; } protected: - explicit Position(::google::protobuf::Arena* arena); - Position(::google::protobuf::Arena* arena, const Position& from); + explicit RespondZoomRangeRequest(::google::protobuf::Arena* arena); + RespondZoomRangeRequest(::google::protobuf::Arena* arena, const RespondZoomRangeRequest& from); public: static const ClassData _class_data_; @@ -5484,58 +5340,25 @@ class Position final : // accessors ------------------------------------------------------- enum : int { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAbsoluteAltitudeMFieldNumber = 3, - kRelativeAltitudeMFieldNumber = 4, + kZoomRangeFeedbackFieldNumber = 1, }; - // double latitude_deg = 1; - void clear_latitude_deg() ; - double latitude_deg() const; - void set_latitude_deg(double value); - - private: - double _internal_latitude_deg() const; - void _internal_set_latitude_deg(double value); - - public: - // double longitude_deg = 2; - void clear_longitude_deg() ; - double longitude_deg() const; - void set_longitude_deg(double value); - - private: - double _internal_longitude_deg() const; - void _internal_set_longitude_deg(double value); - - public: - // float absolute_altitude_m = 3; - void clear_absolute_altitude_m() ; - float absolute_altitude_m() const; - void set_absolute_altitude_m(float value); - - private: - float _internal_absolute_altitude_m() const; - void _internal_set_absolute_altitude_m(float value); - - public: - // float relative_altitude_m = 4; - void clear_relative_altitude_m() ; - float relative_altitude_m() const; - void set_relative_altitude_m(float value); + // .mavsdk.rpc.camera_server.CameraFeedback zoom_range_feedback = 1; + void clear_zoom_range_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback zoom_range_feedback() const; + void set_zoom_range_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - float _internal_relative_altitude_m() const; - void _internal_set_relative_altitude_m(float value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_zoom_range_feedback() const; + void _internal_set_zoom_range_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Position) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondZoomRangeRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 4, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -5552,10 +5375,7 @@ class Position final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - double latitude_deg_; - double longitude_deg_; - float absolute_altitude_m_; - float relative_altitude_m_; + int zoom_range_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -5563,26 +5383,26 @@ class Position final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Information final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { +class RespondZoomOutStartRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondZoomOutStartRequest) */ { public: - inline Information() : Information(nullptr) {} - ~Information() override; + inline RespondZoomOutStartRequest() : RespondZoomOutStartRequest(nullptr) {} + ~RespondZoomOutStartRequest() override; template - explicit PROTOBUF_CONSTEXPR Information(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondZoomOutStartRequest(::google::protobuf::internal::ConstantInitialized); - inline Information(const Information& from) - : Information(nullptr, from) {} - Information(Information&& from) noexcept - : Information() { + inline RespondZoomOutStartRequest(const RespondZoomOutStartRequest& from) + : RespondZoomOutStartRequest(nullptr, from) {} + RespondZoomOutStartRequest(RespondZoomOutStartRequest&& from) noexcept + : RespondZoomOutStartRequest() { *this = ::std::move(from); } - inline Information& operator=(const Information& from) { + inline RespondZoomOutStartRequest& operator=(const RespondZoomOutStartRequest& from) { CopyFrom(from); return *this; } - inline Information& operator=(Information&& from) noexcept { + inline RespondZoomOutStartRequest& operator=(RespondZoomOutStartRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5614,20 +5434,20 @@ class Information final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Information& default_instance() { + static const RespondZoomOutStartRequest& default_instance() { return *internal_default_instance(); } - static inline const Information* internal_default_instance() { - return reinterpret_cast( - &_Information_default_instance_); + static inline const RespondZoomOutStartRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondZoomOutStartRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 46; + 52; - friend void swap(Information& a, Information& b) { + friend void swap(RespondZoomOutStartRequest& a, RespondZoomOutStartRequest& b) { a.Swap(&b); } - inline void Swap(Information* other) { + inline void Swap(RespondZoomOutStartRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5640,7 +5460,7 @@ class Information final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Information* other) { + void UnsafeArenaSwap(RespondZoomOutStartRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5648,14 +5468,14 @@ class Information final : // implements Message ---------------------------------------------- - Information* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondZoomOutStartRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Information& from); + void CopyFrom(const RespondZoomOutStartRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Information& from) { - Information::MergeImpl(*this, from); + void MergeFrom( const RespondZoomOutStartRequest& from) { + RespondZoomOutStartRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -5673,16 +5493,16 @@ class Information final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Information* other); + void InternalSwap(RespondZoomOutStartRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Information"; + return "mavsdk.rpc.camera_server.RespondZoomOutStartRequest"; } protected: - explicit Information(::google::protobuf::Arena* arena); - Information(::google::protobuf::Arena* arena, const Information& from); + explicit RespondZoomOutStartRequest(::google::protobuf::Arena* arena); + RespondZoomOutStartRequest(::google::protobuf::Arena* arena, const RespondZoomOutStartRequest& from); public: static const ClassData _class_data_; @@ -5695,160 +5515,26 @@ class Information final : // accessors ------------------------------------------------------- enum : int { - kVendorNameFieldNumber = 1, - kModelNameFieldNumber = 2, - kFirmwareVersionFieldNumber = 3, - kDefinitionFileUriFieldNumber = 11, - kFocalLengthMmFieldNumber = 4, - kHorizontalSensorSizeMmFieldNumber = 5, - kVerticalSensorSizeMmFieldNumber = 6, - kHorizontalResolutionPxFieldNumber = 7, - kVerticalResolutionPxFieldNumber = 8, - kLensIdFieldNumber = 9, - kDefinitionFileVersionFieldNumber = 10, + kZoomOutStartFeedbackFieldNumber = 1, }; - // string vendor_name = 1; - void clear_vendor_name() ; - const std::string& vendor_name() const; - template - void set_vendor_name(Arg_&& arg, Args_... args); - std::string* mutable_vendor_name(); - PROTOBUF_NODISCARD std::string* release_vendor_name(); - void set_allocated_vendor_name(std::string* value); - - private: - const std::string& _internal_vendor_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( - const std::string& value); - std::string* _internal_mutable_vendor_name(); - - public: - // string model_name = 2; - void clear_model_name() ; - const std::string& model_name() const; - template - void set_model_name(Arg_&& arg, Args_... args); - std::string* mutable_model_name(); - PROTOBUF_NODISCARD std::string* release_model_name(); - void set_allocated_model_name(std::string* value); - - private: - const std::string& _internal_model_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_model_name( - const std::string& value); - std::string* _internal_mutable_model_name(); - - public: - // 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); - - private: - float _internal_focal_length_mm() const; - void _internal_set_focal_length_mm(float value); - - public: - // 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); - - private: - float _internal_horizontal_sensor_size_mm() const; - void _internal_set_horizontal_sensor_size_mm(float value); - - public: - // 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); - - private: - float _internal_vertical_sensor_size_mm() const; - void _internal_set_vertical_sensor_size_mm(float value); - - public: - // uint32 horizontal_resolution_px = 7; - void clear_horizontal_resolution_px() ; - ::uint32_t horizontal_resolution_px() const; - void set_horizontal_resolution_px(::uint32_t value); - - private: - ::uint32_t _internal_horizontal_resolution_px() const; - void _internal_set_horizontal_resolution_px(::uint32_t value); - - public: - // uint32 vertical_resolution_px = 8; - void clear_vertical_resolution_px() ; - ::uint32_t vertical_resolution_px() const; - void set_vertical_resolution_px(::uint32_t value); - - private: - ::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); + // .mavsdk.rpc.camera_server.CameraFeedback zoom_out_start_feedback = 1; + void clear_zoom_out_start_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback zoom_out_start_feedback() const; + void set_zoom_out_start_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - ::uint32_t _internal_definition_file_version() const; - void _internal_set_definition_file_version(::uint32_t value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_zoom_out_start_feedback() const; + void _internal_set_zoom_out_start_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondZoomOutStartRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 4, 11, 0, - 109, 2> + 0, 1, 0, + 0, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -5864,17 +5550,7 @@ class Information final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::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_; + int zoom_out_start_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -5882,26 +5558,26 @@ class Information final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class FormatStorageResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.FormatStorageResponse) */ { +class RespondZoomInStartRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondZoomInStartRequest) */ { public: - inline FormatStorageResponse() : FormatStorageResponse(nullptr) {} - ~FormatStorageResponse() override; + inline RespondZoomInStartRequest() : RespondZoomInStartRequest(nullptr) {} + ~RespondZoomInStartRequest() override; template - explicit PROTOBUF_CONSTEXPR FormatStorageResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondZoomInStartRequest(::google::protobuf::internal::ConstantInitialized); - inline FormatStorageResponse(const FormatStorageResponse& from) - : FormatStorageResponse(nullptr, from) {} - FormatStorageResponse(FormatStorageResponse&& from) noexcept - : FormatStorageResponse() { + inline RespondZoomInStartRequest(const RespondZoomInStartRequest& from) + : RespondZoomInStartRequest(nullptr, from) {} + RespondZoomInStartRequest(RespondZoomInStartRequest&& from) noexcept + : RespondZoomInStartRequest() { *this = ::std::move(from); } - inline FormatStorageResponse& operator=(const FormatStorageResponse& from) { + inline RespondZoomInStartRequest& operator=(const RespondZoomInStartRequest& from) { CopyFrom(from); return *this; } - inline FormatStorageResponse& operator=(FormatStorageResponse&& from) noexcept { + inline RespondZoomInStartRequest& operator=(RespondZoomInStartRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5933,20 +5609,20 @@ class FormatStorageResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const FormatStorageResponse& default_instance() { + static const RespondZoomInStartRequest& default_instance() { return *internal_default_instance(); } - static inline const FormatStorageResponse* internal_default_instance() { - return reinterpret_cast( - &_FormatStorageResponse_default_instance_); + static inline const RespondZoomInStartRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondZoomInStartRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 39; + 48; - friend void swap(FormatStorageResponse& a, FormatStorageResponse& b) { + friend void swap(RespondZoomInStartRequest& a, RespondZoomInStartRequest& b) { a.Swap(&b); } - inline void Swap(FormatStorageResponse* other) { + inline void Swap(RespondZoomInStartRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5959,7 +5635,7 @@ class FormatStorageResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(FormatStorageResponse* other) { + void UnsafeArenaSwap(RespondZoomInStartRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5967,14 +5643,14 @@ class FormatStorageResponse final : // implements Message ---------------------------------------------- - FormatStorageResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondZoomInStartRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FormatStorageResponse& from); + void CopyFrom(const RespondZoomInStartRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FormatStorageResponse& from) { - FormatStorageResponse::MergeImpl(*this, from); + void MergeFrom( const RespondZoomInStartRequest& from) { + RespondZoomInStartRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -5992,16 +5668,16 @@ class FormatStorageResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(FormatStorageResponse* other); + void InternalSwap(RespondZoomInStartRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.FormatStorageResponse"; + return "mavsdk.rpc.camera_server.RespondZoomInStartRequest"; } protected: - explicit FormatStorageResponse(::google::protobuf::Arena* arena); - FormatStorageResponse(::google::protobuf::Arena* arena, const FormatStorageResponse& from); + explicit RespondZoomInStartRequest(::google::protobuf::Arena* arena); + RespondZoomInStartRequest(::google::protobuf::Arena* arena, const RespondZoomInStartRequest& from); public: static const ClassData _class_data_; @@ -6014,19 +5690,19 @@ class FormatStorageResponse final : // accessors ------------------------------------------------------- enum : int { - kStorageIdFieldNumber = 1, + kZoomInStartFeedbackFieldNumber = 1, }; - // int32 storage_id = 1; - void clear_storage_id() ; - ::int32_t storage_id() const; - void set_storage_id(::int32_t value); + // .mavsdk.rpc.camera_server.CameraFeedback zoom_in_start_feedback = 1; + void clear_zoom_in_start_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback zoom_in_start_feedback() const; + void set_zoom_in_start_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - ::int32_t _internal_storage_id() const; - void _internal_set_storage_id(::int32_t value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_zoom_in_start_feedback() const; + void _internal_set_zoom_in_start_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.FormatStorageResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondZoomInStartRequest) private: class _Internal; @@ -6049,7 +5725,7 @@ class FormatStorageResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t storage_id_; + int zoom_in_start_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -6057,26 +5733,26 @@ class FormatStorageResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CaptureStatusResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatusResponse) */ { +class RespondStopVideoStreamingRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) */ { public: - inline CaptureStatusResponse() : CaptureStatusResponse(nullptr) {} - ~CaptureStatusResponse() override; + inline RespondStopVideoStreamingRequest() : RespondStopVideoStreamingRequest(nullptr) {} + ~RespondStopVideoStreamingRequest() override; template - explicit PROTOBUF_CONSTEXPR CaptureStatusResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStopVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); - inline CaptureStatusResponse(const CaptureStatusResponse& from) - : CaptureStatusResponse(nullptr, from) {} - CaptureStatusResponse(CaptureStatusResponse&& from) noexcept - : CaptureStatusResponse() { + inline RespondStopVideoStreamingRequest(const RespondStopVideoStreamingRequest& from) + : RespondStopVideoStreamingRequest(nullptr, from) {} + RespondStopVideoStreamingRequest(RespondStopVideoStreamingRequest&& from) noexcept + : RespondStopVideoStreamingRequest() { *this = ::std::move(from); } - inline CaptureStatusResponse& operator=(const CaptureStatusResponse& from) { + inline RespondStopVideoStreamingRequest& operator=(const RespondStopVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline CaptureStatusResponse& operator=(CaptureStatusResponse&& from) noexcept { + inline RespondStopVideoStreamingRequest& operator=(RespondStopVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6108,20 +5784,20 @@ class CaptureStatusResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CaptureStatusResponse& default_instance() { + static const RespondStopVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const CaptureStatusResponse* internal_default_instance() { - return reinterpret_cast( - &_CaptureStatusResponse_default_instance_); + static inline const RespondStopVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStopVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 35; + 24; - friend void swap(CaptureStatusResponse& a, CaptureStatusResponse& b) { + friend void swap(RespondStopVideoStreamingRequest& a, RespondStopVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(CaptureStatusResponse* other) { + inline void Swap(RespondStopVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6134,7 +5810,7 @@ class CaptureStatusResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CaptureStatusResponse* other) { + void UnsafeArenaSwap(RespondStopVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6142,14 +5818,14 @@ class CaptureStatusResponse final : // implements Message ---------------------------------------------- - CaptureStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStopVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const CaptureStatusResponse& from); + void CopyFrom(const RespondStopVideoStreamingRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const CaptureStatusResponse& from) { - CaptureStatusResponse::MergeImpl(*this, from); + void MergeFrom( const RespondStopVideoStreamingRequest& from) { + RespondStopVideoStreamingRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -6167,16 +5843,16 @@ class CaptureStatusResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(CaptureStatusResponse* other); + void InternalSwap(RespondStopVideoStreamingRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CaptureStatusResponse"; + return "mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest"; } protected: - explicit CaptureStatusResponse(::google::protobuf::Arena* arena); - CaptureStatusResponse(::google::protobuf::Arena* arena, const CaptureStatusResponse& from); + explicit RespondStopVideoStreamingRequest(::google::protobuf::Arena* arena); + RespondStopVideoStreamingRequest(::google::protobuf::Arena* arena, const RespondStopVideoStreamingRequest& from); public: static const ClassData _class_data_; @@ -6189,19 +5865,19 @@ class CaptureStatusResponse final : // accessors ------------------------------------------------------- enum : int { - kReservedFieldNumber = 1, + kStopVideoStreamingFeedbackFieldNumber = 1, }; - // int32 reserved = 1; - void clear_reserved() ; - ::int32_t reserved() const; - void set_reserved(::int32_t value); + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; + void clear_stop_video_streaming_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback stop_video_streaming_feedback() const; + void set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - ::int32_t _internal_reserved() const; - void _internal_set_reserved(::int32_t value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_stop_video_streaming_feedback() const; + void _internal_set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatusResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) private: class _Internal; @@ -6224,7 +5900,7 @@ class CaptureStatusResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t reserved_; + int stop_video_streaming_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -6232,26 +5908,26 @@ class CaptureStatusResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CaptureStatus final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatus) */ { +class RespondStopVideoRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoRequest) */ { public: - inline CaptureStatus() : CaptureStatus(nullptr) {} - ~CaptureStatus() override; + inline RespondStopVideoRequest() : RespondStopVideoRequest(nullptr) {} + ~RespondStopVideoRequest() override; template - explicit PROTOBUF_CONSTEXPR CaptureStatus(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStopVideoRequest(::google::protobuf::internal::ConstantInitialized); - inline CaptureStatus(const CaptureStatus& from) - : CaptureStatus(nullptr, from) {} - CaptureStatus(CaptureStatus&& from) noexcept - : CaptureStatus() { + inline RespondStopVideoRequest(const RespondStopVideoRequest& from) + : RespondStopVideoRequest(nullptr, from) {} + RespondStopVideoRequest(RespondStopVideoRequest&& from) noexcept + : RespondStopVideoRequest() { *this = ::std::move(from); } - inline CaptureStatus& operator=(const CaptureStatus& from) { + inline RespondStopVideoRequest& operator=(const RespondStopVideoRequest& from) { CopyFrom(from); return *this; } - inline CaptureStatus& operator=(CaptureStatus&& from) noexcept { + inline RespondStopVideoRequest& operator=(RespondStopVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6283,20 +5959,20 @@ class CaptureStatus final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CaptureStatus& default_instance() { + static const RespondStopVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const CaptureStatus* internal_default_instance() { - return reinterpret_cast( - &_CaptureStatus_default_instance_); + static inline const RespondStopVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStopVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 53; + 16; - friend void swap(CaptureStatus& a, CaptureStatus& b) { + friend void swap(RespondStopVideoRequest& a, RespondStopVideoRequest& b) { a.Swap(&b); } - inline void Swap(CaptureStatus* other) { + inline void Swap(RespondStopVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6309,7 +5985,7 @@ class CaptureStatus final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CaptureStatus* other) { + void UnsafeArenaSwap(RespondStopVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6317,14 +5993,14 @@ class CaptureStatus final : // implements Message ---------------------------------------------- - CaptureStatus* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStopVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const CaptureStatus& from); + void CopyFrom(const RespondStopVideoRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const CaptureStatus& from) { - CaptureStatus::MergeImpl(*this, from); + void MergeFrom( const RespondStopVideoRequest& from) { + RespondStopVideoRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -6342,16 +6018,16 @@ class CaptureStatus final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(CaptureStatus* other); + void InternalSwap(RespondStopVideoRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CaptureStatus"; + return "mavsdk.rpc.camera_server.RespondStopVideoRequest"; } protected: - explicit CaptureStatus(::google::protobuf::Arena* arena); - CaptureStatus(::google::protobuf::Arena* arena, const CaptureStatus& from); + explicit RespondStopVideoRequest(::google::protobuf::Arena* arena); + RespondStopVideoRequest(::google::protobuf::Arena* arena, const RespondStopVideoRequest& from); public: static const ClassData _class_data_; @@ -6361,125 +6037,28 @@ class CaptureStatus final : // nested types ---------------------------------------------------- - using ImageStatus = CaptureStatus_ImageStatus; - static constexpr ImageStatus IMAGE_STATUS_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_IDLE; - static constexpr ImageStatus IMAGE_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_CAPTURE_IN_PROGRESS; - static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IDLE; - static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IN_PROGRESS; - static inline bool ImageStatus_IsValid(int value) { - return CaptureStatus_ImageStatus_IsValid(value); - } - static constexpr ImageStatus ImageStatus_MIN = CaptureStatus_ImageStatus_ImageStatus_MIN; - static constexpr ImageStatus ImageStatus_MAX = CaptureStatus_ImageStatus_ImageStatus_MAX; - static constexpr int ImageStatus_ARRAYSIZE = CaptureStatus_ImageStatus_ImageStatus_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* ImageStatus_descriptor() { - return CaptureStatus_ImageStatus_descriptor(); - } - template - static inline const std::string& ImageStatus_Name(T value) { - return CaptureStatus_ImageStatus_Name(value); - } - static inline bool ImageStatus_Parse(absl::string_view name, ImageStatus* value) { - return CaptureStatus_ImageStatus_Parse(name, value); - } - - using VideoStatus = CaptureStatus_VideoStatus; - static constexpr VideoStatus VIDEO_STATUS_IDLE = CaptureStatus_VideoStatus_VIDEO_STATUS_IDLE; - static constexpr VideoStatus VIDEO_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_VideoStatus_VIDEO_STATUS_CAPTURE_IN_PROGRESS; - static inline bool VideoStatus_IsValid(int value) { - return CaptureStatus_VideoStatus_IsValid(value); - } - static constexpr VideoStatus VideoStatus_MIN = CaptureStatus_VideoStatus_VideoStatus_MIN; - static constexpr VideoStatus VideoStatus_MAX = CaptureStatus_VideoStatus_VideoStatus_MAX; - static constexpr int VideoStatus_ARRAYSIZE = CaptureStatus_VideoStatus_VideoStatus_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* VideoStatus_descriptor() { - return CaptureStatus_VideoStatus_descriptor(); - } - template - static inline const std::string& VideoStatus_Name(T value) { - return CaptureStatus_VideoStatus_Name(value); - } - static inline bool VideoStatus_Parse(absl::string_view name, VideoStatus* value) { - return CaptureStatus_VideoStatus_Parse(name, value); - } - // accessors ------------------------------------------------------- enum : int { - kImageIntervalSFieldNumber = 1, - kRecordingTimeSFieldNumber = 2, - kAvailableCapacityMibFieldNumber = 3, - kImageStatusFieldNumber = 4, - kVideoStatusFieldNumber = 5, - kImageCountFieldNumber = 6, + kStopVideoFeedbackFieldNumber = 1, }; - // float image_interval_s = 1; - void clear_image_interval_s() ; - float image_interval_s() const; - void set_image_interval_s(float value); - - private: - float _internal_image_interval_s() const; - void _internal_set_image_interval_s(float value); - - public: - // float recording_time_s = 2; - void clear_recording_time_s() ; - float recording_time_s() const; - void set_recording_time_s(float value); - - private: - float _internal_recording_time_s() const; - void _internal_set_recording_time_s(float value); - - public: - // float available_capacity_mib = 3; - void clear_available_capacity_mib() ; - float available_capacity_mib() const; - void set_available_capacity_mib(float value); - - private: - float _internal_available_capacity_mib() const; - void _internal_set_available_capacity_mib(float value); - - public: - // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; - void clear_image_status() ; - ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus image_status() const; - void set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); - - private: - ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus _internal_image_status() const; - void _internal_set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); - - public: - // .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; - void clear_video_status() ; - ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus video_status() const; - void set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); - - private: - ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus _internal_video_status() const; - void _internal_set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); - - public: - // int32 image_count = 6; - void clear_image_count() ; - ::int32_t image_count() const; - void set_image_count(::int32_t value); + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; + void clear_stop_video_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback stop_video_feedback() const; + void set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - ::int32_t _internal_image_count() const; - void _internal_set_image_count(::int32_t value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_stop_video_feedback() const; + void _internal_set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatus) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 6, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -6496,12 +6075,7 @@ class CaptureStatus final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float image_interval_s_; - float recording_time_s_; - float available_capacity_mib_; - int image_status_; - int video_status_; - ::int32_t image_count_; + int stop_video_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -6509,26 +6083,26 @@ class CaptureStatus final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CameraServerResult final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CameraServerResult) */ { +class RespondStartVideoStreamingRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) */ { public: - inline CameraServerResult() : CameraServerResult(nullptr) {} - ~CameraServerResult() override; + inline RespondStartVideoStreamingRequest() : RespondStartVideoStreamingRequest(nullptr) {} + ~RespondStartVideoStreamingRequest() override; template - explicit PROTOBUF_CONSTEXPR CameraServerResult(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStartVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); - inline CameraServerResult(const CameraServerResult& from) - : CameraServerResult(nullptr, from) {} - CameraServerResult(CameraServerResult&& from) noexcept - : CameraServerResult() { + inline RespondStartVideoStreamingRequest(const RespondStartVideoStreamingRequest& from) + : RespondStartVideoStreamingRequest(nullptr, from) {} + RespondStartVideoStreamingRequest(RespondStartVideoStreamingRequest&& from) noexcept + : RespondStartVideoStreamingRequest() { *this = ::std::move(from); } - inline CameraServerResult& operator=(const CameraServerResult& from) { + inline RespondStartVideoStreamingRequest& operator=(const RespondStartVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline CameraServerResult& operator=(CameraServerResult&& from) noexcept { + inline RespondStartVideoStreamingRequest& operator=(RespondStartVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6560,20 +6134,20 @@ class CameraServerResult final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CameraServerResult& default_instance() { + static const RespondStartVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const CameraServerResult* internal_default_instance() { - return reinterpret_cast( - &_CameraServerResult_default_instance_); + static inline const RespondStartVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStartVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 51; + 20; - friend void swap(CameraServerResult& a, CameraServerResult& b) { + friend void swap(RespondStartVideoStreamingRequest& a, RespondStartVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(CameraServerResult* other) { + inline void Swap(RespondStartVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6586,7 +6160,7 @@ class CameraServerResult final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CameraServerResult* other) { + void UnsafeArenaSwap(RespondStartVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6594,14 +6168,14 @@ class CameraServerResult final : // implements Message ---------------------------------------------- - CameraServerResult* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStartVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const CameraServerResult& from); + void CopyFrom(const RespondStartVideoStreamingRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const CameraServerResult& from) { - CameraServerResult::MergeImpl(*this, from); + void MergeFrom( const RespondStartVideoStreamingRequest& from) { + RespondStartVideoStreamingRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -6619,16 +6193,16 @@ class CameraServerResult final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(CameraServerResult* other); + void InternalSwap(RespondStartVideoStreamingRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CameraServerResult"; + return "mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest"; } protected: - explicit CameraServerResult(::google::protobuf::Arena* arena); - CameraServerResult(::google::protobuf::Arena* arena, const CameraServerResult& from); + explicit RespondStartVideoStreamingRequest(::google::protobuf::Arena* arena); + RespondStartVideoStreamingRequest(::google::protobuf::Arena* arena, const RespondStartVideoStreamingRequest& from); public: static const ClassData _class_data_; @@ -6638,73 +6212,29 @@ class CameraServerResult final : // nested types ---------------------------------------------------- - using Result = CameraServerResult_Result; - static constexpr Result RESULT_UNKNOWN = CameraServerResult_Result_RESULT_UNKNOWN; - static constexpr Result RESULT_SUCCESS = CameraServerResult_Result_RESULT_SUCCESS; - static constexpr Result RESULT_IN_PROGRESS = CameraServerResult_Result_RESULT_IN_PROGRESS; - static constexpr Result RESULT_BUSY = CameraServerResult_Result_RESULT_BUSY; - static constexpr Result RESULT_DENIED = CameraServerResult_Result_RESULT_DENIED; - static constexpr Result RESULT_ERROR = CameraServerResult_Result_RESULT_ERROR; - static constexpr Result RESULT_TIMEOUT = CameraServerResult_Result_RESULT_TIMEOUT; - static constexpr Result RESULT_WRONG_ARGUMENT = CameraServerResult_Result_RESULT_WRONG_ARGUMENT; - static constexpr Result RESULT_NO_SYSTEM = CameraServerResult_Result_RESULT_NO_SYSTEM; - static inline bool Result_IsValid(int value) { - return CameraServerResult_Result_IsValid(value); - } - static constexpr Result Result_MIN = CameraServerResult_Result_Result_MIN; - static constexpr Result Result_MAX = CameraServerResult_Result_Result_MAX; - static constexpr int Result_ARRAYSIZE = CameraServerResult_Result_Result_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* Result_descriptor() { - return CameraServerResult_Result_descriptor(); - } - template - static inline const std::string& Result_Name(T value) { - return CameraServerResult_Result_Name(value); - } - static inline bool Result_Parse(absl::string_view name, Result* value) { - return CameraServerResult_Result_Parse(name, value); - } - // accessors ------------------------------------------------------- enum : int { - kResultStrFieldNumber = 2, - kResultFieldNumber = 1, + kStartVideoStreamingFeedbackFieldNumber = 1, }; - // string result_str = 2; - void clear_result_str() ; - const std::string& result_str() const; - template - void set_result_str(Arg_&& arg, Args_... args); - std::string* mutable_result_str(); - PROTOBUF_NODISCARD std::string* release_result_str(); - void set_allocated_result_str(std::string* value); - - private: - const std::string& _internal_result_str() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_result_str( - const std::string& value); - std::string* _internal_mutable_result_str(); - - public: - // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; - void clear_result() ; - ::mavsdk::rpc::camera_server::CameraServerResult_Result result() const; - void set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); + // .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; + void clear_start_video_streaming_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback start_video_streaming_feedback() const; + void set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - ::mavsdk::rpc::camera_server::CameraServerResult_Result _internal_result() const; - void _internal_set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_start_video_streaming_feedback() const; + void _internal_set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CameraServerResult) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, - 62, 2> + 0, 1, 0, + 0, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -6720,8 +6250,7 @@ class CameraServerResult final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::ArenaStringPtr result_str_; - int result_; + int start_video_streaming_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -6729,26 +6258,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 RespondStartVideoRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoRequest) */ { public: - inline SetVideoStreamingResponse() : SetVideoStreamingResponse(nullptr) {} - ~SetVideoStreamingResponse() override; + inline RespondStartVideoRequest() : RespondStartVideoRequest(nullptr) {} + ~RespondStartVideoRequest() override; template - explicit PROTOBUF_CONSTEXPR SetVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStartVideoRequest(::google::protobuf::internal::ConstantInitialized); - inline SetVideoStreamingResponse(const SetVideoStreamingResponse& from) - : SetVideoStreamingResponse(nullptr, from) {} - SetVideoStreamingResponse(SetVideoStreamingResponse&& from) noexcept - : SetVideoStreamingResponse() { + inline RespondStartVideoRequest(const RespondStartVideoRequest& from) + : RespondStartVideoRequest(nullptr, from) {} + RespondStartVideoRequest(RespondStartVideoRequest&& from) noexcept + : RespondStartVideoRequest() { *this = ::std::move(from); } - inline SetVideoStreamingResponse& operator=(const SetVideoStreamingResponse& from) { + inline RespondStartVideoRequest& operator=(const RespondStartVideoRequest& from) { CopyFrom(from); return *this; } - inline SetVideoStreamingResponse& operator=(SetVideoStreamingResponse&& from) noexcept { + inline RespondStartVideoRequest& operator=(RespondStartVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6780,20 +6309,20 @@ class SetVideoStreamingResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetVideoStreamingResponse& default_instance() { + static const RespondStartVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const SetVideoStreamingResponse* internal_default_instance() { - return reinterpret_cast( - &_SetVideoStreamingResponse_default_instance_); + static inline const RespondStartVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStartVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 3; + 12; - friend void swap(SetVideoStreamingResponse& a, SetVideoStreamingResponse& b) { + friend void swap(RespondStartVideoRequest& a, RespondStartVideoRequest& b) { a.Swap(&b); } - inline void Swap(SetVideoStreamingResponse* other) { + inline void Swap(RespondStartVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6806,7 +6335,7 @@ class SetVideoStreamingResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetVideoStreamingResponse* other) { + void UnsafeArenaSwap(RespondStartVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6814,14 +6343,14 @@ class SetVideoStreamingResponse final : // implements Message ---------------------------------------------- - SetVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStartVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetVideoStreamingResponse& from); + void CopyFrom(const RespondStartVideoRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetVideoStreamingResponse& from) { - SetVideoStreamingResponse::MergeImpl(*this, from); + void MergeFrom( const RespondStartVideoRequest& from) { + RespondStartVideoRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -6839,16 +6368,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(RespondStartVideoRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetVideoStreamingResponse"; + return "mavsdk.rpc.camera_server.RespondStartVideoRequest"; } protected: - explicit SetVideoStreamingResponse(::google::protobuf::Arena* arena); - SetVideoStreamingResponse(::google::protobuf::Arena* arena, const SetVideoStreamingResponse& from); + explicit RespondStartVideoRequest(::google::protobuf::Arena* arena); + RespondStartVideoRequest(::google::protobuf::Arena* arena, const RespondStartVideoRequest& from); public: static const ClassData _class_data_; @@ -6861,30 +6390,25 @@ class SetVideoStreamingResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kStartVideoFeedbackFieldNumber = 1, }; - // .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.CameraFeedback start_video_feedback = 1; + void clear_start_video_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback start_video_feedback() const; + void set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_start_video_feedback() const; + void _internal_set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -6901,35 +6425,34 @@ class SetVideoStreamingResponse 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_; + int start_video_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; 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 RespondSetModeRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondSetModeRequest) */ { public: - inline SetVideoStreamingRequest() : SetVideoStreamingRequest(nullptr) {} - ~SetVideoStreamingRequest() override; + inline RespondSetModeRequest() : RespondSetModeRequest(nullptr) {} + ~RespondSetModeRequest() override; template - explicit PROTOBUF_CONSTEXPR SetVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondSetModeRequest(::google::protobuf::internal::ConstantInitialized); - inline SetVideoStreamingRequest(const SetVideoStreamingRequest& from) - : SetVideoStreamingRequest(nullptr, from) {} - SetVideoStreamingRequest(SetVideoStreamingRequest&& from) noexcept - : SetVideoStreamingRequest() { + inline RespondSetModeRequest(const RespondSetModeRequest& from) + : RespondSetModeRequest(nullptr, from) {} + RespondSetModeRequest(RespondSetModeRequest&& from) noexcept + : RespondSetModeRequest() { *this = ::std::move(from); } - inline SetVideoStreamingRequest& operator=(const SetVideoStreamingRequest& from) { + inline RespondSetModeRequest& operator=(const RespondSetModeRequest& from) { CopyFrom(from); return *this; } - inline SetVideoStreamingRequest& operator=(SetVideoStreamingRequest&& from) noexcept { + inline RespondSetModeRequest& operator=(RespondSetModeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6961,20 +6484,20 @@ class SetVideoStreamingRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetVideoStreamingRequest& default_instance() { + static const RespondSetModeRequest& default_instance() { return *internal_default_instance(); } - static inline const SetVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_SetVideoStreamingRequest_default_instance_); + static inline const RespondSetModeRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondSetModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 2; + 28; - friend void swap(SetVideoStreamingRequest& a, SetVideoStreamingRequest& b) { + friend void swap(RespondSetModeRequest& a, RespondSetModeRequest& b) { a.Swap(&b); } - inline void Swap(SetVideoStreamingRequest* other) { + inline void Swap(RespondSetModeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6987,7 +6510,7 @@ class SetVideoStreamingRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetVideoStreamingRequest* other) { + void UnsafeArenaSwap(RespondSetModeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6995,14 +6518,14 @@ class SetVideoStreamingRequest final : // implements Message ---------------------------------------------- - SetVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondSetModeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetVideoStreamingRequest& from); + void CopyFrom(const RespondSetModeRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetVideoStreamingRequest& from) { - SetVideoStreamingRequest::MergeImpl(*this, from); + void MergeFrom( const RespondSetModeRequest& from) { + RespondSetModeRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7020,16 +6543,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(RespondSetModeRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetVideoStreamingRequest"; + return "mavsdk.rpc.camera_server.RespondSetModeRequest"; } protected: - explicit SetVideoStreamingRequest(::google::protobuf::Arena* arena); - SetVideoStreamingRequest(::google::protobuf::Arena* arena, const SetVideoStreamingRequest& from); + explicit RespondSetModeRequest(::google::protobuf::Arena* arena); + RespondSetModeRequest(::google::protobuf::Arena* arena, const RespondSetModeRequest& from); public: static const ClassData _class_data_; @@ -7042,30 +6565,25 @@ class SetVideoStreamingRequest final : // accessors ------------------------------------------------------- enum : int { - kVideoStreamingFieldNumber = 1, + kSetModeFeedbackFieldNumber = 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.CameraFeedback set_mode_feedback = 1; + void clear_set_mode_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback set_mode_feedback() const; + void set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - const ::mavsdk::rpc::camera_server::VideoStreaming& _internal_video_streaming() const; - ::mavsdk::rpc::camera_server::VideoStreaming* _internal_mutable_video_streaming(); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_set_mode_feedback() const; + void _internal_set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondSetModeRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -7082,35 +6600,34 @@ class SetVideoStreamingRequest 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_; + int set_mode_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::VideoStreaming* video_streaming_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SetInformationResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInformationResponse) */ { +class RespondResetSettingsRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondResetSettingsRequest) */ { public: - inline SetInformationResponse() : SetInformationResponse(nullptr) {} - ~SetInformationResponse() override; + inline RespondResetSettingsRequest() : RespondResetSettingsRequest(nullptr) {} + ~RespondResetSettingsRequest() override; template - explicit PROTOBUF_CONSTEXPR SetInformationResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondResetSettingsRequest(::google::protobuf::internal::ConstantInitialized); - inline SetInformationResponse(const SetInformationResponse& from) - : SetInformationResponse(nullptr, from) {} - SetInformationResponse(SetInformationResponse&& from) noexcept - : SetInformationResponse() { + inline RespondResetSettingsRequest(const RespondResetSettingsRequest& from) + : RespondResetSettingsRequest(nullptr, from) {} + RespondResetSettingsRequest(RespondResetSettingsRequest&& from) noexcept + : RespondResetSettingsRequest() { *this = ::std::move(from); } - inline SetInformationResponse& operator=(const SetInformationResponse& from) { + inline RespondResetSettingsRequest& operator=(const RespondResetSettingsRequest& from) { CopyFrom(from); return *this; } - inline SetInformationResponse& operator=(SetInformationResponse&& from) noexcept { + inline RespondResetSettingsRequest& operator=(RespondResetSettingsRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7142,20 +6659,20 @@ class SetInformationResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetInformationResponse& default_instance() { + static const RespondResetSettingsRequest& default_instance() { return *internal_default_instance(); } - static inline const SetInformationResponse* internal_default_instance() { - return reinterpret_cast( - &_SetInformationResponse_default_instance_); + static inline const RespondResetSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondResetSettingsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 1; + 44; - friend void swap(SetInformationResponse& a, SetInformationResponse& b) { + friend void swap(RespondResetSettingsRequest& a, RespondResetSettingsRequest& b) { a.Swap(&b); } - inline void Swap(SetInformationResponse* other) { + inline void Swap(RespondResetSettingsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7168,7 +6685,7 @@ class SetInformationResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetInformationResponse* other) { + void UnsafeArenaSwap(RespondResetSettingsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7176,14 +6693,14 @@ class SetInformationResponse final : // implements Message ---------------------------------------------- - SetInformationResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondResetSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetInformationResponse& from); + void CopyFrom(const RespondResetSettingsRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetInformationResponse& from) { - SetInformationResponse::MergeImpl(*this, from); + void MergeFrom( const RespondResetSettingsRequest& from) { + RespondResetSettingsRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7201,16 +6718,16 @@ class SetInformationResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetInformationResponse* other); + void InternalSwap(RespondResetSettingsRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetInformationResponse"; + return "mavsdk.rpc.camera_server.RespondResetSettingsRequest"; } protected: - explicit SetInformationResponse(::google::protobuf::Arena* arena); - SetInformationResponse(::google::protobuf::Arena* arena, const SetInformationResponse& from); + explicit RespondResetSettingsRequest(::google::protobuf::Arena* arena); + RespondResetSettingsRequest(::google::protobuf::Arena* arena, const RespondResetSettingsRequest& from); public: static const ClassData _class_data_; @@ -7223,30 +6740,25 @@ class SetInformationResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kResetSettingsFeedbackFieldNumber = 1, }; - // .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.CameraFeedback reset_settings_feedback = 1; + void clear_reset_settings_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback reset_settings_feedback() const; + void set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_reset_settings_feedback() const; + void _internal_set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInformationResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondResetSettingsRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -7263,35 +6775,34 @@ class SetInformationResponse 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_; + int reset_settings_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SetInformationRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInformationRequest) */ { +class RespondFormatStorageRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondFormatStorageRequest) */ { public: - inline SetInformationRequest() : SetInformationRequest(nullptr) {} - ~SetInformationRequest() override; + inline RespondFormatStorageRequest() : RespondFormatStorageRequest(nullptr) {} + ~RespondFormatStorageRequest() override; template - explicit PROTOBUF_CONSTEXPR SetInformationRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondFormatStorageRequest(::google::protobuf::internal::ConstantInitialized); - inline SetInformationRequest(const SetInformationRequest& from) - : SetInformationRequest(nullptr, from) {} - SetInformationRequest(SetInformationRequest&& from) noexcept - : SetInformationRequest() { + inline RespondFormatStorageRequest(const RespondFormatStorageRequest& from) + : RespondFormatStorageRequest(nullptr, from) {} + RespondFormatStorageRequest(RespondFormatStorageRequest&& from) noexcept + : RespondFormatStorageRequest() { *this = ::std::move(from); } - inline SetInformationRequest& operator=(const SetInformationRequest& from) { + inline RespondFormatStorageRequest& operator=(const RespondFormatStorageRequest& from) { CopyFrom(from); return *this; } - inline SetInformationRequest& operator=(SetInformationRequest&& from) noexcept { + inline RespondFormatStorageRequest& operator=(RespondFormatStorageRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7323,20 +6834,20 @@ class SetInformationRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetInformationRequest& default_instance() { + static const RespondFormatStorageRequest& default_instance() { return *internal_default_instance(); } - static inline const SetInformationRequest* internal_default_instance() { - return reinterpret_cast( - &_SetInformationRequest_default_instance_); + static inline const RespondFormatStorageRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondFormatStorageRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 0; + 40; - friend void swap(SetInformationRequest& a, SetInformationRequest& b) { + friend void swap(RespondFormatStorageRequest& a, RespondFormatStorageRequest& b) { a.Swap(&b); } - inline void Swap(SetInformationRequest* other) { + inline void Swap(RespondFormatStorageRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7349,7 +6860,7 @@ class SetInformationRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetInformationRequest* other) { + void UnsafeArenaSwap(RespondFormatStorageRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7357,14 +6868,14 @@ class SetInformationRequest final : // implements Message ---------------------------------------------- - SetInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondFormatStorageRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetInformationRequest& from); + void CopyFrom(const RespondFormatStorageRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetInformationRequest& from) { - SetInformationRequest::MergeImpl(*this, from); + void MergeFrom( const RespondFormatStorageRequest& from) { + RespondFormatStorageRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7382,16 +6893,16 @@ class SetInformationRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetInformationRequest* other); + void InternalSwap(RespondFormatStorageRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetInformationRequest"; + return "mavsdk.rpc.camera_server.RespondFormatStorageRequest"; } protected: - explicit SetInformationRequest(::google::protobuf::Arena* arena); - SetInformationRequest(::google::protobuf::Arena* arena, const SetInformationRequest& from); + explicit RespondFormatStorageRequest(::google::protobuf::Arena* arena); + RespondFormatStorageRequest(::google::protobuf::Arena* arena, const RespondFormatStorageRequest& from); public: static const ClassData _class_data_; @@ -7404,30 +6915,25 @@ class SetInformationRequest final : // accessors ------------------------------------------------------- enum : int { - kInformationFieldNumber = 1, + kFormatStorageFeedbackFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.Information information = 1; - bool has_information() const; - void clear_information() ; - const ::mavsdk::rpc::camera_server::Information& information() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Information* release_information(); - ::mavsdk::rpc::camera_server::Information* mutable_information(); - void set_allocated_information(::mavsdk::rpc::camera_server::Information* value); - void unsafe_arena_set_allocated_information(::mavsdk::rpc::camera_server::Information* value); - ::mavsdk::rpc::camera_server::Information* unsafe_arena_release_information(); + // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; + void clear_format_storage_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback format_storage_feedback() const; + void set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - const ::mavsdk::rpc::camera_server::Information& _internal_information() const; - ::mavsdk::rpc::camera_server::Information* _internal_mutable_information(); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_format_storage_feedback() const; + void _internal_set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInformationRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondFormatStorageRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -7444,35 +6950,34 @@ class SetInformationRequest 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_; + int format_storage_feedback_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::Information* information_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SetInProgressResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInProgressResponse) */ { +class ResetSettingsResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ResetSettingsResponse) */ { public: - inline SetInProgressResponse() : SetInProgressResponse(nullptr) {} - ~SetInProgressResponse() override; + inline ResetSettingsResponse() : ResetSettingsResponse(nullptr) {} + ~ResetSettingsResponse() override; template - explicit PROTOBUF_CONSTEXPR SetInProgressResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ResetSettingsResponse(::google::protobuf::internal::ConstantInitialized); - inline SetInProgressResponse(const SetInProgressResponse& from) - : SetInProgressResponse(nullptr, from) {} - SetInProgressResponse(SetInProgressResponse&& from) noexcept - : SetInProgressResponse() { + inline ResetSettingsResponse(const ResetSettingsResponse& from) + : ResetSettingsResponse(nullptr, from) {} + ResetSettingsResponse(ResetSettingsResponse&& from) noexcept + : ResetSettingsResponse() { *this = ::std::move(from); } - inline SetInProgressResponse& operator=(const SetInProgressResponse& from) { + inline ResetSettingsResponse& operator=(const ResetSettingsResponse& from) { CopyFrom(from); return *this; } - inline SetInProgressResponse& operator=(SetInProgressResponse&& from) noexcept { + inline ResetSettingsResponse& operator=(ResetSettingsResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7504,20 +7009,20 @@ class SetInProgressResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetInProgressResponse& default_instance() { + static const ResetSettingsResponse& default_instance() { return *internal_default_instance(); } - static inline const SetInProgressResponse* internal_default_instance() { - return reinterpret_cast( - &_SetInProgressResponse_default_instance_); + static inline const ResetSettingsResponse* internal_default_instance() { + return reinterpret_cast( + &_ResetSettingsResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 5; + 43; - friend void swap(SetInProgressResponse& a, SetInProgressResponse& b) { + friend void swap(ResetSettingsResponse& a, ResetSettingsResponse& b) { a.Swap(&b); } - inline void Swap(SetInProgressResponse* other) { + inline void Swap(ResetSettingsResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7530,7 +7035,7 @@ class SetInProgressResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetInProgressResponse* other) { + void UnsafeArenaSwap(ResetSettingsResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7538,14 +7043,14 @@ class SetInProgressResponse final : // implements Message ---------------------------------------------- - SetInProgressResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ResetSettingsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetInProgressResponse& from); + void CopyFrom(const ResetSettingsResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetInProgressResponse& from) { - SetInProgressResponse::MergeImpl(*this, from); + void MergeFrom( const ResetSettingsResponse& from) { + ResetSettingsResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7563,16 +7068,16 @@ class SetInProgressResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetInProgressResponse* other); + void InternalSwap(ResetSettingsResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetInProgressResponse"; + return "mavsdk.rpc.camera_server.ResetSettingsResponse"; } protected: - explicit SetInProgressResponse(::google::protobuf::Arena* arena); - SetInProgressResponse(::google::protobuf::Arena* arena, const SetInProgressResponse& from); + explicit ResetSettingsResponse(::google::protobuf::Arena* arena); + ResetSettingsResponse(::google::protobuf::Arena* arena, const ResetSettingsResponse& from); public: static const ClassData _class_data_; @@ -7585,30 +7090,25 @@ class SetInProgressResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kReservedFieldNumber = 1, }; - // .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(); + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInProgressResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ResetSettingsResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -7625,35 +7125,34 @@ class SetInProgressResponse 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_; + ::int32_t reserved_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondTakePhotoResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { +class Quaternion final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Quaternion) */ { public: - inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} - ~RespondTakePhotoResponse() override; + inline Quaternion() : Quaternion(nullptr) {} + ~Quaternion() override; template - explicit PROTOBUF_CONSTEXPR RespondTakePhotoResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Quaternion(::google::protobuf::internal::ConstantInitialized); - inline RespondTakePhotoResponse(const RespondTakePhotoResponse& from) - : RespondTakePhotoResponse(nullptr, from) {} - RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept - : RespondTakePhotoResponse() { + inline Quaternion(const Quaternion& from) + : Quaternion(nullptr, from) {} + Quaternion(Quaternion&& from) noexcept + : Quaternion() { *this = ::std::move(from); } - inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { + inline Quaternion& operator=(const Quaternion& from) { CopyFrom(from); return *this; } - inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& from) noexcept { + inline Quaternion& operator=(Quaternion&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7685,20 +7184,20 @@ class RespondTakePhotoResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondTakePhotoResponse& default_instance() { + static const Quaternion& default_instance() { return *internal_default_instance(); } - static inline const RespondTakePhotoResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondTakePhotoResponse_default_instance_); + static inline const Quaternion* internal_default_instance() { + return reinterpret_cast( + &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 9; + 65; - friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { + friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); } - inline void Swap(RespondTakePhotoResponse* other) { + inline void Swap(Quaternion* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7711,7 +7210,7 @@ class RespondTakePhotoResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondTakePhotoResponse* other) { + void UnsafeArenaSwap(Quaternion* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7719,14 +7218,14 @@ class RespondTakePhotoResponse final : // implements Message ---------------------------------------------- - RespondTakePhotoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Quaternion* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondTakePhotoResponse& from); + void CopyFrom(const Quaternion& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondTakePhotoResponse& from) { - RespondTakePhotoResponse::MergeImpl(*this, from); + void MergeFrom( const Quaternion& from) { + Quaternion::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7744,16 +7243,16 @@ class RespondTakePhotoResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondTakePhotoResponse* other); + void InternalSwap(Quaternion* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; + return "mavsdk.rpc.camera_server.Quaternion"; } protected: - explicit RespondTakePhotoResponse(::google::protobuf::Arena* arena); - RespondTakePhotoResponse(::google::protobuf::Arena* arena, const RespondTakePhotoResponse& from); + explicit Quaternion(::google::protobuf::Arena* arena); + Quaternion(::google::protobuf::Arena* arena, const Quaternion& from); public: static const ClassData _class_data_; @@ -7766,30 +7265,58 @@ class RespondTakePhotoResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kWFieldNumber = 1, + kXFieldNumber = 2, + kYFieldNumber = 3, + kZFieldNumber = 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(); + // float w = 1; + void clear_w() ; + float w() const; + void set_w(float value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + float _internal_w() const; + void _internal_set_w(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // float x = 2; + void clear_x() ; + float x() const; + void set_x(float value); + + private: + float _internal_x() const; + void _internal_set_x(float value); + + public: + // float y = 3; + void clear_y() ; + float y() const; + void set_y(float value); + + private: + float _internal_y() const; + void _internal_set_y(float value); + + public: + // float z = 4; + void clear_z() ; + float z() const; + void set_z(float value); + + private: + float _internal_z() const; + void _internal_set_z(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Quaternion) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 2, 4, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -7806,35 +7333,37 @@ class RespondTakePhotoResponse 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_; + float w_; + float x_; + float y_; + float z_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStorageInformationResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationResponse) */ { +class Position final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Position) */ { public: - inline RespondStorageInformationResponse() : RespondStorageInformationResponse(nullptr) {} - ~RespondStorageInformationResponse() override; + inline Position() : Position(nullptr) {} + ~Position() override; template - explicit PROTOBUF_CONSTEXPR RespondStorageInformationResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Position(::google::protobuf::internal::ConstantInitialized); - inline RespondStorageInformationResponse(const RespondStorageInformationResponse& from) - : RespondStorageInformationResponse(nullptr, from) {} - RespondStorageInformationResponse(RespondStorageInformationResponse&& from) noexcept - : RespondStorageInformationResponse() { + inline Position(const Position& from) + : Position(nullptr, from) {} + Position(Position&& from) noexcept + : Position() { *this = ::std::move(from); } - inline RespondStorageInformationResponse& operator=(const RespondStorageInformationResponse& from) { + inline Position& operator=(const Position& from) { CopyFrom(from); return *this; } - inline RespondStorageInformationResponse& operator=(RespondStorageInformationResponse&& from) noexcept { + inline Position& operator=(Position&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7866,20 +7395,20 @@ class RespondStorageInformationResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStorageInformationResponse& default_instance() { + static const Position& default_instance() { return *internal_default_instance(); } - static inline const RespondStorageInformationResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondStorageInformationResponse_default_instance_); + static inline const Position* internal_default_instance() { + return reinterpret_cast( + &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 33; + 64; - friend void swap(RespondStorageInformationResponse& a, RespondStorageInformationResponse& b) { + friend void swap(Position& a, Position& b) { a.Swap(&b); } - inline void Swap(RespondStorageInformationResponse* other) { + inline void Swap(Position* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7892,7 +7421,7 @@ class RespondStorageInformationResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStorageInformationResponse* other) { + void UnsafeArenaSwap(Position* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7900,14 +7429,14 @@ class RespondStorageInformationResponse final : // implements Message ---------------------------------------------- - RespondStorageInformationResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Position* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStorageInformationResponse& from); + void CopyFrom(const Position& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStorageInformationResponse& from) { - RespondStorageInformationResponse::MergeImpl(*this, from); + void MergeFrom( const Position& from) { + Position::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7925,16 +7454,16 @@ class RespondStorageInformationResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStorageInformationResponse* other); + void InternalSwap(Position* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStorageInformationResponse"; + return "mavsdk.rpc.camera_server.Position"; } protected: - explicit RespondStorageInformationResponse(::google::protobuf::Arena* arena); - RespondStorageInformationResponse(::google::protobuf::Arena* arena, const RespondStorageInformationResponse& from); + explicit Position(::google::protobuf::Arena* arena); + Position(::google::protobuf::Arena* arena, const Position& from); public: static const ClassData _class_data_; @@ -7947,30 +7476,58 @@ class RespondStorageInformationResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAbsoluteAltitudeMFieldNumber = 3, + kRelativeAltitudeMFieldNumber = 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(); + // double latitude_deg = 1; + void clear_latitude_deg() ; + double latitude_deg() const; + void set_latitude_deg(double value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + double _internal_latitude_deg() const; + void _internal_set_latitude_deg(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + // double longitude_deg = 2; + void clear_longitude_deg() ; + double longitude_deg() const; + void set_longitude_deg(double value); + + private: + double _internal_longitude_deg() const; + void _internal_set_longitude_deg(double value); + + public: + // float absolute_altitude_m = 3; + void clear_absolute_altitude_m() ; + float absolute_altitude_m() const; + void set_absolute_altitude_m(float value); + + private: + float _internal_absolute_altitude_m() const; + void _internal_set_absolute_altitude_m(float value); + + public: + // float relative_altitude_m = 4; + void clear_relative_altitude_m() ; + float relative_altitude_m() const; + void set_relative_altitude_m(float value); + + private: + float _internal_relative_altitude_m() const; + void _internal_set_relative_altitude_m(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Position) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 2, 4, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -7987,35 +7544,37 @@ class RespondStorageInformationResponse 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_; + double latitude_deg_; + double longitude_deg_; + float absolute_altitude_m_; + float relative_altitude_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStorageInformationRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationRequest) */ { +class Information final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { public: - inline RespondStorageInformationRequest() : RespondStorageInformationRequest(nullptr) {} - ~RespondStorageInformationRequest() override; + inline Information() : Information(nullptr) {} + ~Information() override; template - explicit PROTOBUF_CONSTEXPR RespondStorageInformationRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Information(::google::protobuf::internal::ConstantInitialized); - inline RespondStorageInformationRequest(const RespondStorageInformationRequest& from) - : RespondStorageInformationRequest(nullptr, from) {} - RespondStorageInformationRequest(RespondStorageInformationRequest&& from) noexcept - : RespondStorageInformationRequest() { + inline Information(const Information& from) + : Information(nullptr, from) {} + Information(Information&& from) noexcept + : Information() { *this = ::std::move(from); } - inline RespondStorageInformationRequest& operator=(const RespondStorageInformationRequest& from) { + inline Information& operator=(const Information& from) { CopyFrom(from); return *this; } - inline RespondStorageInformationRequest& operator=(RespondStorageInformationRequest&& from) noexcept { + inline Information& operator=(Information&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8047,20 +7606,20 @@ class RespondStorageInformationRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStorageInformationRequest& default_instance() { + static const Information& default_instance() { return *internal_default_instance(); } - static inline const RespondStorageInformationRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondStorageInformationRequest_default_instance_); + static inline const Information* internal_default_instance() { + return reinterpret_cast( + &_Information_default_instance_); } static constexpr int kIndexInFileMessages = - 32; + 62; - friend void swap(RespondStorageInformationRequest& a, RespondStorageInformationRequest& b) { + friend void swap(Information& a, Information& b) { a.Swap(&b); } - inline void Swap(RespondStorageInformationRequest* other) { + inline void Swap(Information* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8073,7 +7632,7 @@ class RespondStorageInformationRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStorageInformationRequest* other) { + void UnsafeArenaSwap(Information* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8081,14 +7640,14 @@ class RespondStorageInformationRequest final : // implements Message ---------------------------------------------- - RespondStorageInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Information* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStorageInformationRequest& from); + void CopyFrom(const Information& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStorageInformationRequest& from) { - RespondStorageInformationRequest::MergeImpl(*this, from); + void MergeFrom( const Information& from) { + Information::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8106,16 +7665,16 @@ class RespondStorageInformationRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStorageInformationRequest* other); + void InternalSwap(Information* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStorageInformationRequest"; + return "mavsdk.rpc.camera_server.Information"; } protected: - explicit RespondStorageInformationRequest(::google::protobuf::Arena* arena); - RespondStorageInformationRequest(::google::protobuf::Arena* arena, const RespondStorageInformationRequest& from); + explicit Information(::google::protobuf::Arena* arena); + Information(::google::protobuf::Arena* arena, const Information& from); public: static const ClassData _class_data_; @@ -8128,42 +7687,160 @@ class RespondStorageInformationRequest final : // accessors ------------------------------------------------------- enum : int { - kStorageInformationFieldNumber = 2, - kStorageInformationFeedbackFieldNumber = 1, - }; - // .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; - bool has_storage_information() const; - void clear_storage_information() ; - const ::mavsdk::rpc::camera_server::StorageInformation& storage_information() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::StorageInformation* release_storage_information(); - ::mavsdk::rpc::camera_server::StorageInformation* mutable_storage_information(); - void set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* value); - void unsafe_arena_set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* value); - ::mavsdk::rpc::camera_server::StorageInformation* unsafe_arena_release_storage_information(); + kVendorNameFieldNumber = 1, + kModelNameFieldNumber = 2, + kFirmwareVersionFieldNumber = 3, + kDefinitionFileUriFieldNumber = 11, + kFocalLengthMmFieldNumber = 4, + kHorizontalSensorSizeMmFieldNumber = 5, + kVerticalSensorSizeMmFieldNumber = 6, + kHorizontalResolutionPxFieldNumber = 7, + kVerticalResolutionPxFieldNumber = 8, + kLensIdFieldNumber = 9, + kDefinitionFileVersionFieldNumber = 10, + }; + // string vendor_name = 1; + void clear_vendor_name() ; + const std::string& vendor_name() const; + template + void set_vendor_name(Arg_&& arg, Args_... args); + std::string* mutable_vendor_name(); + PROTOBUF_NODISCARD std::string* release_vendor_name(); + void set_allocated_vendor_name(std::string* value); private: - const ::mavsdk::rpc::camera_server::StorageInformation& _internal_storage_information() const; - ::mavsdk::rpc::camera_server::StorageInformation* _internal_mutable_storage_information(); + const std::string& _internal_vendor_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( + const std::string& value); + std::string* _internal_mutable_vendor_name(); public: - // .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; - void clear_storage_information_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback storage_information_feedback() const; - void set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // string model_name = 2; + void clear_model_name() ; + const std::string& model_name() const; + template + void set_model_name(Arg_&& arg, Args_... args); + std::string* mutable_model_name(); + PROTOBUF_NODISCARD std::string* release_model_name(); + void set_allocated_model_name(std::string* value); private: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_storage_information_feedback() const; - void _internal_set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + const std::string& _internal_model_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_model_name( + const std::string& value); + std::string* _internal_mutable_model_name(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + // 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); + + private: + float _internal_focal_length_mm() const; + void _internal_set_focal_length_mm(float value); + + public: + // 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); + + private: + float _internal_horizontal_sensor_size_mm() const; + void _internal_set_horizontal_sensor_size_mm(float value); + + public: + // 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); + + private: + float _internal_vertical_sensor_size_mm() const; + void _internal_set_vertical_sensor_size_mm(float value); + + public: + // uint32 horizontal_resolution_px = 7; + void clear_horizontal_resolution_px() ; + ::uint32_t horizontal_resolution_px() const; + void set_horizontal_resolution_px(::uint32_t value); + + private: + ::uint32_t _internal_horizontal_resolution_px() const; + void _internal_set_horizontal_resolution_px(::uint32_t value); + + public: + // uint32 vertical_resolution_px = 8; + void clear_vertical_resolution_px() ; + ::uint32_t vertical_resolution_px() const; + void set_vertical_resolution_px(::uint32_t value); + + private: + ::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_server.Information) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 1, - 0, 2> + 4, 11, 0, + 109, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -8179,36 +7856,44 @@ class RespondStorageInformationRequest 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::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_; - ::mavsdk::rpc::camera_server::StorageInformation* storage_information_; - int storage_information_feedback_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStopVideoStreamingResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) */ { +class FormatStorageResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.FormatStorageResponse) */ { public: - inline RespondStopVideoStreamingResponse() : RespondStopVideoStreamingResponse(nullptr) {} - ~RespondStopVideoStreamingResponse() override; + inline FormatStorageResponse() : FormatStorageResponse(nullptr) {} + ~FormatStorageResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondStopVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR FormatStorageResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondStopVideoStreamingResponse(const RespondStopVideoStreamingResponse& from) - : RespondStopVideoStreamingResponse(nullptr, from) {} - RespondStopVideoStreamingResponse(RespondStopVideoStreamingResponse&& from) noexcept - : RespondStopVideoStreamingResponse() { + inline FormatStorageResponse(const FormatStorageResponse& from) + : FormatStorageResponse(nullptr, from) {} + FormatStorageResponse(FormatStorageResponse&& from) noexcept + : FormatStorageResponse() { *this = ::std::move(from); } - inline RespondStopVideoStreamingResponse& operator=(const RespondStopVideoStreamingResponse& from) { + inline FormatStorageResponse& operator=(const FormatStorageResponse& from) { CopyFrom(from); return *this; } - inline RespondStopVideoStreamingResponse& operator=(RespondStopVideoStreamingResponse&& from) noexcept { + inline FormatStorageResponse& operator=(FormatStorageResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8240,20 +7925,20 @@ class RespondStopVideoStreamingResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStopVideoStreamingResponse& default_instance() { + static const FormatStorageResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondStopVideoStreamingResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondStopVideoStreamingResponse_default_instance_); + static inline const FormatStorageResponse* internal_default_instance() { + return reinterpret_cast( + &_FormatStorageResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 25; + 39; - friend void swap(RespondStopVideoStreamingResponse& a, RespondStopVideoStreamingResponse& b) { + friend void swap(FormatStorageResponse& a, FormatStorageResponse& b) { a.Swap(&b); } - inline void Swap(RespondStopVideoStreamingResponse* other) { + inline void Swap(FormatStorageResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8266,7 +7951,7 @@ class RespondStopVideoStreamingResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStopVideoStreamingResponse* other) { + void UnsafeArenaSwap(FormatStorageResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8274,14 +7959,14 @@ class RespondStopVideoStreamingResponse final : // implements Message ---------------------------------------------- - RespondStopVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + FormatStorageResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStopVideoStreamingResponse& from); + void CopyFrom(const FormatStorageResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStopVideoStreamingResponse& from) { - RespondStopVideoStreamingResponse::MergeImpl(*this, from); + void MergeFrom( const FormatStorageResponse& from) { + FormatStorageResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8299,16 +7984,16 @@ class RespondStopVideoStreamingResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStopVideoStreamingResponse* other); + void InternalSwap(FormatStorageResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse"; + return "mavsdk.rpc.camera_server.FormatStorageResponse"; } protected: - explicit RespondStopVideoStreamingResponse(::google::protobuf::Arena* arena); - RespondStopVideoStreamingResponse(::google::protobuf::Arena* arena, const RespondStopVideoStreamingResponse& from); + explicit FormatStorageResponse(::google::protobuf::Arena* arena); + FormatStorageResponse(::google::protobuf::Arena* arena, const FormatStorageResponse& from); public: static const ClassData _class_data_; @@ -8321,30 +8006,25 @@ class RespondStopVideoStreamingResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kStorageIdFieldNumber = 1, }; - // .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(); + // int32 storage_id = 1; + void clear_storage_id() ; + ::int32_t storage_id() const; + void set_storage_id(::int32_t value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + ::int32_t _internal_storage_id() const; + void _internal_set_storage_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.FormatStorageResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -8361,35 +8041,34 @@ class RespondStopVideoStreamingResponse 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_; + ::int32_t storage_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStopVideoResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoResponse) */ { +class CaptureStatusResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatusResponse) */ { public: - inline RespondStopVideoResponse() : RespondStopVideoResponse(nullptr) {} - ~RespondStopVideoResponse() override; + inline CaptureStatusResponse() : CaptureStatusResponse(nullptr) {} + ~CaptureStatusResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondStopVideoResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR CaptureStatusResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondStopVideoResponse(const RespondStopVideoResponse& from) - : RespondStopVideoResponse(nullptr, from) {} - RespondStopVideoResponse(RespondStopVideoResponse&& from) noexcept - : RespondStopVideoResponse() { + inline CaptureStatusResponse(const CaptureStatusResponse& from) + : CaptureStatusResponse(nullptr, from) {} + CaptureStatusResponse(CaptureStatusResponse&& from) noexcept + : CaptureStatusResponse() { *this = ::std::move(from); } - inline RespondStopVideoResponse& operator=(const RespondStopVideoResponse& from) { + inline CaptureStatusResponse& operator=(const CaptureStatusResponse& from) { CopyFrom(from); return *this; } - inline RespondStopVideoResponse& operator=(RespondStopVideoResponse&& from) noexcept { + inline CaptureStatusResponse& operator=(CaptureStatusResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8421,20 +8100,20 @@ class RespondStopVideoResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStopVideoResponse& default_instance() { + static const CaptureStatusResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondStopVideoResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondStopVideoResponse_default_instance_); + static inline const CaptureStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_CaptureStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 17; + 35; - friend void swap(RespondStopVideoResponse& a, RespondStopVideoResponse& b) { + friend void swap(CaptureStatusResponse& a, CaptureStatusResponse& b) { a.Swap(&b); } - inline void Swap(RespondStopVideoResponse* other) { + inline void Swap(CaptureStatusResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8447,7 +8126,7 @@ class RespondStopVideoResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStopVideoResponse* other) { + void UnsafeArenaSwap(CaptureStatusResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8455,14 +8134,14 @@ class RespondStopVideoResponse final : // implements Message ---------------------------------------------- - RespondStopVideoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + CaptureStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStopVideoResponse& from); + void CopyFrom(const CaptureStatusResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStopVideoResponse& from) { - RespondStopVideoResponse::MergeImpl(*this, from); + void MergeFrom( const CaptureStatusResponse& from) { + CaptureStatusResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8480,16 +8159,16 @@ class RespondStopVideoResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStopVideoResponse* other); + void InternalSwap(CaptureStatusResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStopVideoResponse"; + return "mavsdk.rpc.camera_server.CaptureStatusResponse"; } protected: - explicit RespondStopVideoResponse(::google::protobuf::Arena* arena); - RespondStopVideoResponse(::google::protobuf::Arena* arena, const RespondStopVideoResponse& from); + explicit CaptureStatusResponse(::google::protobuf::Arena* arena); + CaptureStatusResponse(::google::protobuf::Arena* arena, const CaptureStatusResponse& from); public: static const ClassData _class_data_; @@ -8502,30 +8181,25 @@ class RespondStopVideoResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kReservedFieldNumber = 1, }; - // .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(); + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatusResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -8542,35 +8216,34 @@ class RespondStopVideoResponse 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_; + ::int32_t reserved_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStartVideoStreamingResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) */ { +class CaptureStatus final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatus) */ { public: - inline RespondStartVideoStreamingResponse() : RespondStartVideoStreamingResponse(nullptr) {} - ~RespondStartVideoStreamingResponse() override; + inline CaptureStatus() : CaptureStatus(nullptr) {} + ~CaptureStatus() override; template - explicit PROTOBUF_CONSTEXPR RespondStartVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR CaptureStatus(::google::protobuf::internal::ConstantInitialized); - inline RespondStartVideoStreamingResponse(const RespondStartVideoStreamingResponse& from) - : RespondStartVideoStreamingResponse(nullptr, from) {} - RespondStartVideoStreamingResponse(RespondStartVideoStreamingResponse&& from) noexcept - : RespondStartVideoStreamingResponse() { + inline CaptureStatus(const CaptureStatus& from) + : CaptureStatus(nullptr, from) {} + CaptureStatus(CaptureStatus&& from) noexcept + : CaptureStatus() { *this = ::std::move(from); } - inline RespondStartVideoStreamingResponse& operator=(const RespondStartVideoStreamingResponse& from) { + inline CaptureStatus& operator=(const CaptureStatus& from) { CopyFrom(from); return *this; } - inline RespondStartVideoStreamingResponse& operator=(RespondStartVideoStreamingResponse&& from) noexcept { + inline CaptureStatus& operator=(CaptureStatus&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8602,20 +8275,20 @@ class RespondStartVideoStreamingResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStartVideoStreamingResponse& default_instance() { + static const CaptureStatus& default_instance() { return *internal_default_instance(); } - static inline const RespondStartVideoStreamingResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondStartVideoStreamingResponse_default_instance_); + static inline const CaptureStatus* internal_default_instance() { + return reinterpret_cast( + &_CaptureStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 21; + 69; - friend void swap(RespondStartVideoStreamingResponse& a, RespondStartVideoStreamingResponse& b) { + friend void swap(CaptureStatus& a, CaptureStatus& b) { a.Swap(&b); } - inline void Swap(RespondStartVideoStreamingResponse* other) { + inline void Swap(CaptureStatus* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8628,7 +8301,7 @@ class RespondStartVideoStreamingResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStartVideoStreamingResponse* other) { + void UnsafeArenaSwap(CaptureStatus* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8636,14 +8309,14 @@ class RespondStartVideoStreamingResponse final : // implements Message ---------------------------------------------- - RespondStartVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + CaptureStatus* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStartVideoStreamingResponse& from); + void CopyFrom(const CaptureStatus& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStartVideoStreamingResponse& from) { - RespondStartVideoStreamingResponse::MergeImpl(*this, from); + void MergeFrom( const CaptureStatus& from) { + CaptureStatus::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8661,16 +8334,16 @@ class RespondStartVideoStreamingResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStartVideoStreamingResponse* other); + void InternalSwap(CaptureStatus* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse"; + return "mavsdk.rpc.camera_server.CaptureStatus"; } protected: - explicit RespondStartVideoStreamingResponse(::google::protobuf::Arena* arena); - RespondStartVideoStreamingResponse(::google::protobuf::Arena* arena, const RespondStartVideoStreamingResponse& from); + explicit CaptureStatus(::google::protobuf::Arena* arena); + CaptureStatus(::google::protobuf::Arena* arena, const CaptureStatus& from); public: static const ClassData _class_data_; @@ -8680,33 +8353,125 @@ class RespondStartVideoStreamingResponse final : // nested types ---------------------------------------------------- + using ImageStatus = CaptureStatus_ImageStatus; + static constexpr ImageStatus IMAGE_STATUS_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_IDLE; + static constexpr ImageStatus IMAGE_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_CAPTURE_IN_PROGRESS; + static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IDLE; + static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IN_PROGRESS; + static inline bool ImageStatus_IsValid(int value) { + return CaptureStatus_ImageStatus_IsValid(value); + } + static constexpr ImageStatus ImageStatus_MIN = CaptureStatus_ImageStatus_ImageStatus_MIN; + static constexpr ImageStatus ImageStatus_MAX = CaptureStatus_ImageStatus_ImageStatus_MAX; + static constexpr int ImageStatus_ARRAYSIZE = CaptureStatus_ImageStatus_ImageStatus_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* ImageStatus_descriptor() { + return CaptureStatus_ImageStatus_descriptor(); + } + template + static inline const std::string& ImageStatus_Name(T value) { + return CaptureStatus_ImageStatus_Name(value); + } + static inline bool ImageStatus_Parse(absl::string_view name, ImageStatus* value) { + return CaptureStatus_ImageStatus_Parse(name, value); + } + + using VideoStatus = CaptureStatus_VideoStatus; + static constexpr VideoStatus VIDEO_STATUS_IDLE = CaptureStatus_VideoStatus_VIDEO_STATUS_IDLE; + static constexpr VideoStatus VIDEO_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_VideoStatus_VIDEO_STATUS_CAPTURE_IN_PROGRESS; + static inline bool VideoStatus_IsValid(int value) { + return CaptureStatus_VideoStatus_IsValid(value); + } + static constexpr VideoStatus VideoStatus_MIN = CaptureStatus_VideoStatus_VideoStatus_MIN; + static constexpr VideoStatus VideoStatus_MAX = CaptureStatus_VideoStatus_VideoStatus_MAX; + static constexpr int VideoStatus_ARRAYSIZE = CaptureStatus_VideoStatus_VideoStatus_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* VideoStatus_descriptor() { + return CaptureStatus_VideoStatus_descriptor(); + } + template + static inline const std::string& VideoStatus_Name(T value) { + return CaptureStatus_VideoStatus_Name(value); + } + static inline bool VideoStatus_Parse(absl::string_view name, VideoStatus* value) { + return CaptureStatus_VideoStatus_Parse(name, value); + } + // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kImageIntervalSFieldNumber = 1, + kRecordingTimeSFieldNumber = 2, + kAvailableCapacityMibFieldNumber = 3, + kImageStatusFieldNumber = 4, + kVideoStatusFieldNumber = 5, + kImageCountFieldNumber = 6, }; - // .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(); + // float image_interval_s = 1; + void clear_image_interval_s() ; + float image_interval_s() const; + void set_image_interval_s(float value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + float _internal_image_interval_s() const; + void _internal_set_image_interval_s(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) + // float recording_time_s = 2; + void clear_recording_time_s() ; + float recording_time_s() const; + void set_recording_time_s(float value); + + private: + float _internal_recording_time_s() const; + void _internal_set_recording_time_s(float value); + + public: + // float available_capacity_mib = 3; + void clear_available_capacity_mib() ; + float available_capacity_mib() const; + void set_available_capacity_mib(float value); + + private: + float _internal_available_capacity_mib() const; + void _internal_set_available_capacity_mib(float value); + + public: + // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; + void clear_image_status() ; + ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus image_status() const; + void set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); + + private: + ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus _internal_image_status() const; + void _internal_set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); + + public: + // .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; + void clear_video_status() ; + ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus video_status() const; + void set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); + + private: + ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus _internal_video_status() const; + void _internal_set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); + + public: + // int32 image_count = 6; + void clear_image_count() ; + ::int32_t image_count() const; + void set_image_count(::int32_t value); + + private: + ::int32_t _internal_image_count() const; + void _internal_set_image_count(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatus) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 3, 6, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -8723,35 +8488,39 @@ class RespondStartVideoStreamingResponse 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_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + float image_interval_s_; + float recording_time_s_; + float available_capacity_mib_; + int image_status_; + int video_status_; + ::int32_t image_count_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStartVideoResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoResponse) */ { +class CameraServerResult final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CameraServerResult) */ { public: - inline RespondStartVideoResponse() : RespondStartVideoResponse(nullptr) {} - ~RespondStartVideoResponse() override; + inline CameraServerResult() : CameraServerResult(nullptr) {} + ~CameraServerResult() override; template - explicit PROTOBUF_CONSTEXPR RespondStartVideoResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR CameraServerResult(::google::protobuf::internal::ConstantInitialized); - inline RespondStartVideoResponse(const RespondStartVideoResponse& from) - : RespondStartVideoResponse(nullptr, from) {} - RespondStartVideoResponse(RespondStartVideoResponse&& from) noexcept - : RespondStartVideoResponse() { + inline CameraServerResult(const CameraServerResult& from) + : CameraServerResult(nullptr, from) {} + CameraServerResult(CameraServerResult&& from) noexcept + : CameraServerResult() { *this = ::std::move(from); } - inline RespondStartVideoResponse& operator=(const RespondStartVideoResponse& from) { + inline CameraServerResult& operator=(const CameraServerResult& from) { CopyFrom(from); return *this; } - inline RespondStartVideoResponse& operator=(RespondStartVideoResponse&& from) noexcept { + inline CameraServerResult& operator=(CameraServerResult&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8783,20 +8552,20 @@ class RespondStartVideoResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStartVideoResponse& default_instance() { + static const CameraServerResult& default_instance() { return *internal_default_instance(); } - static inline const RespondStartVideoResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondStartVideoResponse_default_instance_); + static inline const CameraServerResult* internal_default_instance() { + return reinterpret_cast( + &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 13; + 67; - friend void swap(RespondStartVideoResponse& a, RespondStartVideoResponse& b) { + friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); } - inline void Swap(RespondStartVideoResponse* other) { + inline void Swap(CameraServerResult* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8809,7 +8578,7 @@ class RespondStartVideoResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStartVideoResponse* other) { + void UnsafeArenaSwap(CameraServerResult* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8817,14 +8586,14 @@ class RespondStartVideoResponse final : // implements Message ---------------------------------------------- - RespondStartVideoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + CameraServerResult* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondStartVideoResponse& from); + void CopyFrom(const CameraServerResult& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondStartVideoResponse& from) { - RespondStartVideoResponse::MergeImpl(*this, from); + void MergeFrom( const CameraServerResult& from) { + CameraServerResult::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8842,16 +8611,16 @@ class RespondStartVideoResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondStartVideoResponse* other); + void InternalSwap(CameraServerResult* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStartVideoResponse"; + return "mavsdk.rpc.camera_server.CameraServerResult"; } protected: - explicit RespondStartVideoResponse(::google::protobuf::Arena* arena); - RespondStartVideoResponse(::google::protobuf::Arena* arena, const RespondStartVideoResponse& from); + explicit CameraServerResult(::google::protobuf::Arena* arena); + CameraServerResult(::google::protobuf::Arena* arena, const CameraServerResult& from); public: static const ClassData _class_data_; @@ -8861,34 +8630,73 @@ class RespondStartVideoResponse final : // nested types ---------------------------------------------------- + using Result = CameraServerResult_Result; + static constexpr Result RESULT_UNKNOWN = CameraServerResult_Result_RESULT_UNKNOWN; + static constexpr Result RESULT_SUCCESS = CameraServerResult_Result_RESULT_SUCCESS; + static constexpr Result RESULT_IN_PROGRESS = CameraServerResult_Result_RESULT_IN_PROGRESS; + static constexpr Result RESULT_BUSY = CameraServerResult_Result_RESULT_BUSY; + static constexpr Result RESULT_DENIED = CameraServerResult_Result_RESULT_DENIED; + static constexpr Result RESULT_ERROR = CameraServerResult_Result_RESULT_ERROR; + static constexpr Result RESULT_TIMEOUT = CameraServerResult_Result_RESULT_TIMEOUT; + static constexpr Result RESULT_WRONG_ARGUMENT = CameraServerResult_Result_RESULT_WRONG_ARGUMENT; + static constexpr Result RESULT_NO_SYSTEM = CameraServerResult_Result_RESULT_NO_SYSTEM; + static inline bool Result_IsValid(int value) { + return CameraServerResult_Result_IsValid(value); + } + static constexpr Result Result_MIN = CameraServerResult_Result_Result_MIN; + static constexpr Result Result_MAX = CameraServerResult_Result_Result_MAX; + static constexpr int Result_ARRAYSIZE = CameraServerResult_Result_Result_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* Result_descriptor() { + return CameraServerResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T value) { + return CameraServerResult_Result_Name(value); + } + static inline bool Result_Parse(absl::string_view name, Result* value) { + return CameraServerResult_Result_Parse(name, value); + } + // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kResultStrFieldNumber = 2, + kResultFieldNumber = 1, }; - // .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(); + // string result_str = 2; + void clear_result_str() ; + const std::string& result_str() const; + template + void set_result_str(Arg_&& arg, Args_... args); + std::string* mutable_result_str(); + PROTOBUF_NODISCARD std::string* release_result_str(); + void set_allocated_result_str(std::string* value); private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + const std::string& _internal_result_str() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_result_str( + const std::string& value); + std::string* _internal_mutable_result_str(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoResponse) + // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; + void clear_result() ; + ::mavsdk::rpc::camera_server::CameraServerResult_Result result() const; + void set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); + + private: + ::mavsdk::rpc::camera_server::CameraServerResult_Result _internal_result() const; + void _internal_set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CameraServerResult) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, - 0, 2> + 1, 2, 0, + 62, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -8904,35 +8712,35 @@ class RespondStartVideoResponse 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::internal::ArenaStringPtr result_str_; + int result_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondSetModeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondSetModeResponse) */ { +class SetVideoStreamingResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetVideoStreamingResponse) */ { public: - inline RespondSetModeResponse() : RespondSetModeResponse(nullptr) {} - ~RespondSetModeResponse() override; + inline SetVideoStreamingResponse() : SetVideoStreamingResponse(nullptr) {} + ~SetVideoStreamingResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondSetModeResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondSetModeResponse(const RespondSetModeResponse& from) - : RespondSetModeResponse(nullptr, from) {} - RespondSetModeResponse(RespondSetModeResponse&& from) noexcept - : RespondSetModeResponse() { + inline SetVideoStreamingResponse(const SetVideoStreamingResponse& from) + : SetVideoStreamingResponse(nullptr, from) {} + SetVideoStreamingResponse(SetVideoStreamingResponse&& from) noexcept + : SetVideoStreamingResponse() { *this = ::std::move(from); } - inline RespondSetModeResponse& operator=(const RespondSetModeResponse& from) { + inline SetVideoStreamingResponse& operator=(const SetVideoStreamingResponse& from) { CopyFrom(from); return *this; } - inline RespondSetModeResponse& operator=(RespondSetModeResponse&& from) noexcept { + inline SetVideoStreamingResponse& operator=(SetVideoStreamingResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8964,20 +8772,20 @@ class RespondSetModeResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondSetModeResponse& default_instance() { + static const SetVideoStreamingResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondSetModeResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondSetModeResponse_default_instance_); + static inline const SetVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_SetVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 29; + 3; - friend void swap(RespondSetModeResponse& a, RespondSetModeResponse& b) { + friend void swap(SetVideoStreamingResponse& a, SetVideoStreamingResponse& b) { a.Swap(&b); } - inline void Swap(RespondSetModeResponse* other) { + inline void Swap(SetVideoStreamingResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8990,7 +8798,7 @@ class RespondSetModeResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondSetModeResponse* other) { + void UnsafeArenaSwap(SetVideoStreamingResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8998,14 +8806,14 @@ class RespondSetModeResponse final : // implements Message ---------------------------------------------- - RespondSetModeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondSetModeResponse& from); + void CopyFrom(const SetVideoStreamingResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondSetModeResponse& from) { - RespondSetModeResponse::MergeImpl(*this, from); + void MergeFrom( const SetVideoStreamingResponse& from) { + SetVideoStreamingResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9023,16 +8831,16 @@ class RespondSetModeResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondSetModeResponse* other); + void InternalSwap(SetVideoStreamingResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondSetModeResponse"; + return "mavsdk.rpc.camera_server.SetVideoStreamingResponse"; } protected: - explicit RespondSetModeResponse(::google::protobuf::Arena* arena); - RespondSetModeResponse(::google::protobuf::Arena* arena, const RespondSetModeResponse& from); + explicit SetVideoStreamingResponse(::google::protobuf::Arena* arena); + SetVideoStreamingResponse(::google::protobuf::Arena* arena, const SetVideoStreamingResponse& from); public: static const ClassData _class_data_; @@ -9062,7 +8870,7 @@ class RespondSetModeResponse final : ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondSetModeResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamingResponse) private: class _Internal; @@ -9094,26 +8902,26 @@ class RespondSetModeResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondResetSettingsResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondResetSettingsResponse) */ { +class SetVideoStreamingRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetVideoStreamingRequest) */ { public: - inline RespondResetSettingsResponse() : RespondResetSettingsResponse(nullptr) {} - ~RespondResetSettingsResponse() override; + inline SetVideoStreamingRequest() : SetVideoStreamingRequest(nullptr) {} + ~SetVideoStreamingRequest() override; template - explicit PROTOBUF_CONSTEXPR RespondResetSettingsResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); - inline RespondResetSettingsResponse(const RespondResetSettingsResponse& from) - : RespondResetSettingsResponse(nullptr, from) {} - RespondResetSettingsResponse(RespondResetSettingsResponse&& from) noexcept - : RespondResetSettingsResponse() { + inline SetVideoStreamingRequest(const SetVideoStreamingRequest& from) + : SetVideoStreamingRequest(nullptr, from) {} + SetVideoStreamingRequest(SetVideoStreamingRequest&& from) noexcept + : SetVideoStreamingRequest() { *this = ::std::move(from); } - inline RespondResetSettingsResponse& operator=(const RespondResetSettingsResponse& from) { + inline SetVideoStreamingRequest& operator=(const SetVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline RespondResetSettingsResponse& operator=(RespondResetSettingsResponse&& from) noexcept { + inline SetVideoStreamingRequest& operator=(SetVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9145,20 +8953,20 @@ class RespondResetSettingsResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondResetSettingsResponse& default_instance() { + static const SetVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const RespondResetSettingsResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondResetSettingsResponse_default_instance_); + static inline const SetVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_SetVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 45; + 2; - friend void swap(RespondResetSettingsResponse& a, RespondResetSettingsResponse& b) { + friend void swap(SetVideoStreamingRequest& a, SetVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(RespondResetSettingsResponse* other) { + inline void Swap(SetVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9171,7 +8979,7 @@ class RespondResetSettingsResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondResetSettingsResponse* other) { + void UnsafeArenaSwap(SetVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9179,14 +8987,14 @@ class RespondResetSettingsResponse final : // implements Message ---------------------------------------------- - RespondResetSettingsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondResetSettingsResponse& from); + void CopyFrom(const SetVideoStreamingRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondResetSettingsResponse& from) { - RespondResetSettingsResponse::MergeImpl(*this, from); + void MergeFrom( const SetVideoStreamingRequest& from) { + SetVideoStreamingRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9204,16 +9012,16 @@ class RespondResetSettingsResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondResetSettingsResponse* other); + void InternalSwap(SetVideoStreamingRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondResetSettingsResponse"; + return "mavsdk.rpc.camera_server.SetVideoStreamingRequest"; } protected: - explicit RespondResetSettingsResponse(::google::protobuf::Arena* arena); - RespondResetSettingsResponse(::google::protobuf::Arena* arena, const RespondResetSettingsResponse& from); + explicit SetVideoStreamingRequest(::google::protobuf::Arena* arena); + SetVideoStreamingRequest(::google::protobuf::Arena* arena, const SetVideoStreamingRequest& from); public: static const ClassData _class_data_; @@ -9226,24 +9034,24 @@ class RespondResetSettingsResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kVideoStreamingFieldNumber = 1, }; - // .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.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(); 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::VideoStreaming& _internal_video_streaming() const; + ::mavsdk::rpc::camera_server::VideoStreaming* _internal_mutable_video_streaming(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamingRequest) private: class _Internal; @@ -9268,33 +9076,33 @@ class RespondResetSettingsResponse 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::VideoStreaming* video_streaming_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondFormatStorageResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondFormatStorageResponse) */ { +class SetInformationResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInformationResponse) */ { public: - inline RespondFormatStorageResponse() : RespondFormatStorageResponse(nullptr) {} - ~RespondFormatStorageResponse() override; + inline SetInformationResponse() : SetInformationResponse(nullptr) {} + ~SetInformationResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondFormatStorageResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetInformationResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondFormatStorageResponse(const RespondFormatStorageResponse& from) - : RespondFormatStorageResponse(nullptr, from) {} - RespondFormatStorageResponse(RespondFormatStorageResponse&& from) noexcept - : RespondFormatStorageResponse() { + inline SetInformationResponse(const SetInformationResponse& from) + : SetInformationResponse(nullptr, from) {} + SetInformationResponse(SetInformationResponse&& from) noexcept + : SetInformationResponse() { *this = ::std::move(from); } - inline RespondFormatStorageResponse& operator=(const RespondFormatStorageResponse& from) { + inline SetInformationResponse& operator=(const SetInformationResponse& from) { CopyFrom(from); return *this; } - inline RespondFormatStorageResponse& operator=(RespondFormatStorageResponse&& from) noexcept { + inline SetInformationResponse& operator=(SetInformationResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9326,20 +9134,20 @@ class RespondFormatStorageResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondFormatStorageResponse& default_instance() { + static const SetInformationResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondFormatStorageResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondFormatStorageResponse_default_instance_); + static inline const SetInformationResponse* internal_default_instance() { + return reinterpret_cast( + &_SetInformationResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 41; + 1; - friend void swap(RespondFormatStorageResponse& a, RespondFormatStorageResponse& b) { + friend void swap(SetInformationResponse& a, SetInformationResponse& b) { a.Swap(&b); } - inline void Swap(RespondFormatStorageResponse* other) { + inline void Swap(SetInformationResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9352,7 +9160,7 @@ class RespondFormatStorageResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondFormatStorageResponse* other) { + void UnsafeArenaSwap(SetInformationResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9360,14 +9168,14 @@ class RespondFormatStorageResponse final : // implements Message ---------------------------------------------- - RespondFormatStorageResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetInformationResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondFormatStorageResponse& from); + void CopyFrom(const SetInformationResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondFormatStorageResponse& from) { - RespondFormatStorageResponse::MergeImpl(*this, from); + void MergeFrom( const SetInformationResponse& from) { + SetInformationResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9385,16 +9193,16 @@ class RespondFormatStorageResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondFormatStorageResponse* other); + void InternalSwap(SetInformationResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondFormatStorageResponse"; + return "mavsdk.rpc.camera_server.SetInformationResponse"; } protected: - explicit RespondFormatStorageResponse(::google::protobuf::Arena* arena); - RespondFormatStorageResponse(::google::protobuf::Arena* arena, const RespondFormatStorageResponse& from); + explicit SetInformationResponse(::google::protobuf::Arena* arena); + SetInformationResponse(::google::protobuf::Arena* arena, const SetInformationResponse& from); public: static const ClassData _class_data_; @@ -9424,7 +9232,7 @@ class RespondFormatStorageResponse final : ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInformationResponse) private: class _Internal; @@ -9456,26 +9264,26 @@ class RespondFormatStorageResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondCaptureStatusResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) */ { +class SetInformationRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInformationRequest) */ { public: - inline RespondCaptureStatusResponse() : RespondCaptureStatusResponse(nullptr) {} - ~RespondCaptureStatusResponse() override; + inline SetInformationRequest() : SetInformationRequest(nullptr) {} + ~SetInformationRequest() override; template - explicit PROTOBUF_CONSTEXPR RespondCaptureStatusResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetInformationRequest(::google::protobuf::internal::ConstantInitialized); - inline RespondCaptureStatusResponse(const RespondCaptureStatusResponse& from) - : RespondCaptureStatusResponse(nullptr, from) {} - RespondCaptureStatusResponse(RespondCaptureStatusResponse&& from) noexcept - : RespondCaptureStatusResponse() { + inline SetInformationRequest(const SetInformationRequest& from) + : SetInformationRequest(nullptr, from) {} + SetInformationRequest(SetInformationRequest&& from) noexcept + : SetInformationRequest() { *this = ::std::move(from); } - inline RespondCaptureStatusResponse& operator=(const RespondCaptureStatusResponse& from) { + inline SetInformationRequest& operator=(const SetInformationRequest& from) { CopyFrom(from); return *this; } - inline RespondCaptureStatusResponse& operator=(RespondCaptureStatusResponse&& from) noexcept { + inline SetInformationRequest& operator=(SetInformationRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9507,20 +9315,20 @@ class RespondCaptureStatusResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondCaptureStatusResponse& default_instance() { + static const SetInformationRequest& default_instance() { return *internal_default_instance(); } - static inline const RespondCaptureStatusResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondCaptureStatusResponse_default_instance_); + static inline const SetInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_SetInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 37; + 0; - friend void swap(RespondCaptureStatusResponse& a, RespondCaptureStatusResponse& b) { + friend void swap(SetInformationRequest& a, SetInformationRequest& b) { a.Swap(&b); } - inline void Swap(RespondCaptureStatusResponse* other) { + inline void Swap(SetInformationRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9533,7 +9341,7 @@ class RespondCaptureStatusResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondCaptureStatusResponse* other) { + void UnsafeArenaSwap(SetInformationRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9541,14 +9349,14 @@ class RespondCaptureStatusResponse final : // implements Message ---------------------------------------------- - RespondCaptureStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondCaptureStatusResponse& from); + void CopyFrom(const SetInformationRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondCaptureStatusResponse& from) { - RespondCaptureStatusResponse::MergeImpl(*this, from); + void MergeFrom( const SetInformationRequest& from) { + SetInformationRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9566,16 +9374,16 @@ class RespondCaptureStatusResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondCaptureStatusResponse* other); + void InternalSwap(SetInformationRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondCaptureStatusResponse"; + return "mavsdk.rpc.camera_server.SetInformationRequest"; } protected: - explicit RespondCaptureStatusResponse(::google::protobuf::Arena* arena); - RespondCaptureStatusResponse(::google::protobuf::Arena* arena, const RespondCaptureStatusResponse& from); + explicit SetInformationRequest(::google::protobuf::Arena* arena); + SetInformationRequest(::google::protobuf::Arena* arena, const SetInformationRequest& from); public: static const ClassData _class_data_; @@ -9588,24 +9396,24 @@ class RespondCaptureStatusResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kInformationFieldNumber = 1, }; - // .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.Information information = 1; + bool has_information() const; + void clear_information() ; + const ::mavsdk::rpc::camera_server::Information& information() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Information* release_information(); + ::mavsdk::rpc::camera_server::Information* mutable_information(); + void set_allocated_information(::mavsdk::rpc::camera_server::Information* value); + void unsafe_arena_set_allocated_information(::mavsdk::rpc::camera_server::Information* value); + ::mavsdk::rpc::camera_server::Information* unsafe_arena_release_information(); 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::Information& _internal_information() const; + ::mavsdk::rpc::camera_server::Information* _internal_mutable_information(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInformationRequest) private: class _Internal; @@ -9630,33 +9438,33 @@ class RespondCaptureStatusResponse 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::Information* information_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondCaptureStatusRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) */ { +class SetInProgressResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInProgressResponse) */ { public: - inline RespondCaptureStatusRequest() : RespondCaptureStatusRequest(nullptr) {} - ~RespondCaptureStatusRequest() override; + inline SetInProgressResponse() : SetInProgressResponse(nullptr) {} + ~SetInProgressResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondCaptureStatusRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetInProgressResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondCaptureStatusRequest(const RespondCaptureStatusRequest& from) - : RespondCaptureStatusRequest(nullptr, from) {} - RespondCaptureStatusRequest(RespondCaptureStatusRequest&& from) noexcept - : RespondCaptureStatusRequest() { + inline SetInProgressResponse(const SetInProgressResponse& from) + : SetInProgressResponse(nullptr, from) {} + SetInProgressResponse(SetInProgressResponse&& from) noexcept + : SetInProgressResponse() { *this = ::std::move(from); } - inline RespondCaptureStatusRequest& operator=(const RespondCaptureStatusRequest& from) { + inline SetInProgressResponse& operator=(const SetInProgressResponse& from) { CopyFrom(from); return *this; } - inline RespondCaptureStatusRequest& operator=(RespondCaptureStatusRequest&& from) noexcept { + inline SetInProgressResponse& operator=(SetInProgressResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9688,20 +9496,20 @@ class RespondCaptureStatusRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondCaptureStatusRequest& default_instance() { + static const SetInProgressResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondCaptureStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondCaptureStatusRequest_default_instance_); + static inline const SetInProgressResponse* internal_default_instance() { + return reinterpret_cast( + &_SetInProgressResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 36; + 5; - friend void swap(RespondCaptureStatusRequest& a, RespondCaptureStatusRequest& b) { + friend void swap(SetInProgressResponse& a, SetInProgressResponse& b) { a.Swap(&b); } - inline void Swap(RespondCaptureStatusRequest* other) { + inline void Swap(SetInProgressResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9714,7 +9522,7 @@ class RespondCaptureStatusRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondCaptureStatusRequest* other) { + void UnsafeArenaSwap(SetInProgressResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9722,14 +9530,14 @@ class RespondCaptureStatusRequest final : // implements Message ---------------------------------------------- - RespondCaptureStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetInProgressResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondCaptureStatusRequest& from); + void CopyFrom(const SetInProgressResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondCaptureStatusRequest& from) { - RespondCaptureStatusRequest::MergeImpl(*this, from); + void MergeFrom( const SetInProgressResponse& from) { + SetInProgressResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9747,16 +9555,16 @@ class RespondCaptureStatusRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondCaptureStatusRequest* other); + void InternalSwap(SetInProgressResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondCaptureStatusRequest"; + return "mavsdk.rpc.camera_server.SetInProgressResponse"; } protected: - explicit RespondCaptureStatusRequest(::google::protobuf::Arena* arena); - RespondCaptureStatusRequest(::google::protobuf::Arena* arena, const RespondCaptureStatusRequest& from); + explicit SetInProgressResponse(::google::protobuf::Arena* arena); + SetInProgressResponse(::google::protobuf::Arena* arena, const SetInProgressResponse& from); public: static const ClassData _class_data_; @@ -9769,41 +9577,30 @@ class RespondCaptureStatusRequest final : // accessors ------------------------------------------------------- enum : int { - kCaptureStatusFieldNumber = 2, - kCaptureStatusFeedbackFieldNumber = 1, + kCameraServerResultFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; - bool has_capture_status() const; - void clear_capture_status() ; - const ::mavsdk::rpc::camera_server::CaptureStatus& capture_status() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureStatus* release_capture_status(); - ::mavsdk::rpc::camera_server::CaptureStatus* mutable_capture_status(); - void set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* value); - void unsafe_arena_set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* value); - ::mavsdk::rpc::camera_server::CaptureStatus* unsafe_arena_release_capture_status(); - - private: - const ::mavsdk::rpc::camera_server::CaptureStatus& _internal_capture_status() const; - ::mavsdk::rpc::camera_server::CaptureStatus* _internal_mutable_capture_status(); - - public: - // .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; - void clear_capture_status_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback capture_status_feedback() const; - void set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // .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: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_capture_status_feedback() const; - void _internal_set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + 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.RespondCaptureStatusRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInProgressResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 1, + 0, 1, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -9822,34 +9619,33 @@ class RespondCaptureStatusRequest 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::CaptureStatus* capture_status_; - int capture_status_feedback_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CaptureInfo final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureInfo) */ { +class RespondZoomStopResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondZoomStopResponse) */ { public: - inline CaptureInfo() : CaptureInfo(nullptr) {} - ~CaptureInfo() override; + inline RespondZoomStopResponse() : RespondZoomStopResponse(nullptr) {} + ~RespondZoomStopResponse() override; template - explicit PROTOBUF_CONSTEXPR CaptureInfo(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondZoomStopResponse(::google::protobuf::internal::ConstantInitialized); - inline CaptureInfo(const CaptureInfo& from) - : CaptureInfo(nullptr, from) {} - CaptureInfo(CaptureInfo&& from) noexcept - : CaptureInfo() { + inline RespondZoomStopResponse(const RespondZoomStopResponse& from) + : RespondZoomStopResponse(nullptr, from) {} + RespondZoomStopResponse(RespondZoomStopResponse&& from) noexcept + : RespondZoomStopResponse() { *this = ::std::move(from); } - inline CaptureInfo& operator=(const CaptureInfo& from) { + inline RespondZoomStopResponse& operator=(const RespondZoomStopResponse& from) { CopyFrom(from); return *this; } - inline CaptureInfo& operator=(CaptureInfo&& from) noexcept { + inline RespondZoomStopResponse& operator=(RespondZoomStopResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9881,20 +9677,20 @@ class CaptureInfo final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CaptureInfo& default_instance() { + static const RespondZoomStopResponse& default_instance() { return *internal_default_instance(); } - static inline const CaptureInfo* internal_default_instance() { - return reinterpret_cast( - &_CaptureInfo_default_instance_); + static inline const RespondZoomStopResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondZoomStopResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 50; + 57; - friend void swap(CaptureInfo& a, CaptureInfo& b) { + friend void swap(RespondZoomStopResponse& a, RespondZoomStopResponse& b) { a.Swap(&b); } - inline void Swap(CaptureInfo* other) { + inline void Swap(RespondZoomStopResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9907,7 +9703,7 @@ class CaptureInfo final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CaptureInfo* other) { + void UnsafeArenaSwap(RespondZoomStopResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9915,14 +9711,14 @@ class CaptureInfo final : // implements Message ---------------------------------------------- - CaptureInfo* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondZoomStopResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const CaptureInfo& from); + void CopyFrom(const RespondZoomStopResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const CaptureInfo& from) { - CaptureInfo::MergeImpl(*this, from); + void MergeFrom( const RespondZoomStopResponse& from) { + RespondZoomStopResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9940,16 +9736,16 @@ class CaptureInfo final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(CaptureInfo* other); + void InternalSwap(RespondZoomStopResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CaptureInfo"; + return "mavsdk.rpc.camera_server.RespondZoomStopResponse"; } protected: - explicit CaptureInfo(::google::protobuf::Arena* arena); - CaptureInfo(::google::protobuf::Arena* arena, const CaptureInfo& from); + explicit RespondZoomStopResponse(::google::protobuf::Arena* arena); + RespondZoomStopResponse(::google::protobuf::Arena* arena, const RespondZoomStopResponse& from); public: static const ClassData _class_data_; @@ -9962,97 +9758,31 @@ class CaptureInfo final : // accessors ------------------------------------------------------- enum : int { - kFileUrlFieldNumber = 6, - kPositionFieldNumber = 1, - kAttitudeQuaternionFieldNumber = 2, - kTimeUtcUsFieldNumber = 3, - kIsSuccessFieldNumber = 4, - kIndexFieldNumber = 5, + kCameraServerResultFieldNumber = 1, }; - // string file_url = 6; - void clear_file_url() ; - const std::string& file_url() const; - template - void set_file_url(Arg_&& arg, Args_... args); - std::string* mutable_file_url(); - PROTOBUF_NODISCARD std::string* release_file_url(); - void set_allocated_file_url(std::string* value); - - private: - const std::string& _internal_file_url() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_file_url( - const std::string& value); - std::string* _internal_mutable_file_url(); - - public: - // .mavsdk.rpc.camera_server.Position position = 1; - bool has_position() const; - void clear_position() ; - const ::mavsdk::rpc::camera_server::Position& position() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Position* release_position(); - ::mavsdk::rpc::camera_server::Position* mutable_position(); - void set_allocated_position(::mavsdk::rpc::camera_server::Position* value); - void unsafe_arena_set_allocated_position(::mavsdk::rpc::camera_server::Position* value); - ::mavsdk::rpc::camera_server::Position* unsafe_arena_release_position(); - - private: - const ::mavsdk::rpc::camera_server::Position& _internal_position() const; - ::mavsdk::rpc::camera_server::Position* _internal_mutable_position(); - - public: - // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; - bool has_attitude_quaternion() const; - void clear_attitude_quaternion() ; - const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Quaternion* release_attitude_quaternion(); - ::mavsdk::rpc::camera_server::Quaternion* mutable_attitude_quaternion(); - void set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* value); - void unsafe_arena_set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* value); - ::mavsdk::rpc::camera_server::Quaternion* unsafe_arena_release_attitude_quaternion(); - - private: - const ::mavsdk::rpc::camera_server::Quaternion& _internal_attitude_quaternion() const; - ::mavsdk::rpc::camera_server::Quaternion* _internal_mutable_attitude_quaternion(); - - public: - // uint64 time_utc_us = 3; - void clear_time_utc_us() ; - ::uint64_t time_utc_us() const; - void set_time_utc_us(::uint64_t value); - - private: - ::uint64_t _internal_time_utc_us() const; - void _internal_set_time_utc_us(::uint64_t value); - - public: - // bool is_success = 4; - void clear_is_success() ; - bool is_success() const; - void set_is_success(bool value); - - private: - bool _internal_is_success() const; - void _internal_set_is_success(bool value); - - public: - // int32 index = 5; - void clear_index() ; - ::int32_t index() const; - void set_index(::int32_t value); + // .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: - ::int32_t _internal_index() const; - void _internal_set_index(::int32_t value); + 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.CaptureInfo) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondZoomStopResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 6, 2, - 53, 2> + 0, 1, 1, + 0, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -10070,38 +9800,33 @@ class CaptureInfo final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::google::protobuf::internal::ArenaStringPtr file_url_; - ::mavsdk::rpc::camera_server::Position* position_; - ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion_; - ::uint64_t time_utc_us_; - bool is_success_; - ::int32_t index_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; 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) */ { +class RespondZoomRangeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondZoomRangeResponse) */ { public: - inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} - ~RespondTakePhotoRequest() override; + inline RespondZoomRangeResponse() : RespondZoomRangeResponse(nullptr) {} + ~RespondZoomRangeResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondTakePhotoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondZoomRangeResponse(::google::protobuf::internal::ConstantInitialized); - inline RespondTakePhotoRequest(const RespondTakePhotoRequest& from) - : RespondTakePhotoRequest(nullptr, from) {} - RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept - : RespondTakePhotoRequest() { + inline RespondZoomRangeResponse(const RespondZoomRangeResponse& from) + : RespondZoomRangeResponse(nullptr, from) {} + RespondZoomRangeResponse(RespondZoomRangeResponse&& from) noexcept + : RespondZoomRangeResponse() { *this = ::std::move(from); } - inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { + inline RespondZoomRangeResponse& operator=(const RespondZoomRangeResponse& from) { CopyFrom(from); return *this; } - inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& from) noexcept { + inline RespondZoomRangeResponse& operator=(RespondZoomRangeResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -10133,20 +9858,20 @@ class RespondTakePhotoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondTakePhotoRequest& default_instance() { + static const RespondZoomRangeResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondTakePhotoRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondTakePhotoRequest_default_instance_); + static inline const RespondZoomRangeResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondZoomRangeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 8; + 61; - friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { + friend void swap(RespondZoomRangeResponse& a, RespondZoomRangeResponse& b) { a.Swap(&b); } - inline void Swap(RespondTakePhotoRequest* other) { + inline void Swap(RespondZoomRangeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -10159,7 +9884,7 @@ class RespondTakePhotoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondTakePhotoRequest* other) { + void UnsafeArenaSwap(RespondZoomRangeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10167,14 +9892,14 @@ class RespondTakePhotoRequest final : // implements Message ---------------------------------------------- - RespondTakePhotoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondZoomRangeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RespondTakePhotoRequest& from); + void CopyFrom(const RespondZoomRangeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RespondTakePhotoRequest& from) { - RespondTakePhotoRequest::MergeImpl(*this, from); + void MergeFrom( const RespondZoomRangeResponse& from) { + RespondZoomRangeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -10192,16 +9917,16 @@ class RespondTakePhotoRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RespondTakePhotoRequest* other); + void InternalSwap(RespondZoomRangeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; + return "mavsdk.rpc.camera_server.RespondZoomRangeResponse"; } protected: - explicit RespondTakePhotoRequest(::google::protobuf::Arena* arena); - RespondTakePhotoRequest(::google::protobuf::Arena* arena, const RespondTakePhotoRequest& from); + explicit RespondZoomRangeResponse(::google::protobuf::Arena* arena); + RespondZoomRangeResponse(::google::protobuf::Arena* arena, const RespondZoomRangeResponse& from); public: static const ClassData _class_data_; @@ -10214,41 +9939,30 @@ class RespondTakePhotoRequest final : // accessors ------------------------------------------------------- enum : int { - kCaptureInfoFieldNumber = 2, - kTakePhotoFeedbackFieldNumber = 1, + kCameraServerResultFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - bool has_capture_info() const; - void clear_capture_info() ; - const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureInfo* release_capture_info(); - ::mavsdk::rpc::camera_server::CaptureInfo* mutable_capture_info(); - void set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* value); - void unsafe_arena_set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* value); - ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); - - private: - const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; - ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); - - public: - // .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; - void clear_take_photo_feedback() ; - ::mavsdk::rpc::camera_server::CameraFeedback take_photo_feedback() const; - void set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + // .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: - ::mavsdk::rpc::camera_server::CameraFeedback _internal_take_photo_feedback() const; - void _internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + 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.RespondTakePhotoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondZoomRangeResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 1, + 0, 1, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -10267,69 +9981,3271 @@ class RespondTakePhotoRequest 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::CaptureInfo* capture_info_; - int take_photo_feedback_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; -}; - -// =================================================================== - +};// ------------------------------------------------------------------- +class RespondZoomOutStartResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondZoomOutStartResponse) */ { + public: + inline RespondZoomOutStartResponse() : RespondZoomOutStartResponse(nullptr) {} + ~RespondZoomOutStartResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondZoomOutStartResponse(::google::protobuf::internal::ConstantInitialized); + inline RespondZoomOutStartResponse(const RespondZoomOutStartResponse& from) + : RespondZoomOutStartResponse(nullptr, from) {} + RespondZoomOutStartResponse(RespondZoomOutStartResponse&& from) noexcept + : RespondZoomOutStartResponse() { + *this = ::std::move(from); + } -// =================================================================== + inline RespondZoomOutStartResponse& operator=(const RespondZoomOutStartResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondZoomOutStartResponse& operator=(RespondZoomOutStartResponse&& 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>(); + } -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wstrict-aliasing" -#endif // __GNUC__ -// ------------------------------------------------------------------- + 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 RespondZoomOutStartResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondZoomOutStartResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondZoomOutStartResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 53; + + friend void swap(RespondZoomOutStartResponse& a, RespondZoomOutStartResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondZoomOutStartResponse* 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(RespondZoomOutStartResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondZoomOutStartResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondZoomOutStartResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondZoomOutStartResponse& from) { + RespondZoomOutStartResponse::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(RespondZoomOutStartResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondZoomOutStartResponse"; + } + protected: + explicit RespondZoomOutStartResponse(::google::protobuf::Arena* arena); + RespondZoomOutStartResponse(::google::protobuf::Arena* arena, const RespondZoomOutStartResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondZoomOutStartResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondZoomInStartResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondZoomInStartResponse) */ { + public: + inline RespondZoomInStartResponse() : RespondZoomInStartResponse(nullptr) {} + ~RespondZoomInStartResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondZoomInStartResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondZoomInStartResponse(const RespondZoomInStartResponse& from) + : RespondZoomInStartResponse(nullptr, from) {} + RespondZoomInStartResponse(RespondZoomInStartResponse&& from) noexcept + : RespondZoomInStartResponse() { + *this = ::std::move(from); + } + + inline RespondZoomInStartResponse& operator=(const RespondZoomInStartResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondZoomInStartResponse& operator=(RespondZoomInStartResponse&& 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 RespondZoomInStartResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondZoomInStartResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondZoomInStartResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 49; + + friend void swap(RespondZoomInStartResponse& a, RespondZoomInStartResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondZoomInStartResponse* 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(RespondZoomInStartResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondZoomInStartResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondZoomInStartResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondZoomInStartResponse& from) { + RespondZoomInStartResponse::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(RespondZoomInStartResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondZoomInStartResponse"; + } + protected: + explicit RespondZoomInStartResponse(::google::protobuf::Arena* arena); + RespondZoomInStartResponse(::google::protobuf::Arena* arena, const RespondZoomInStartResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondZoomInStartResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondTakePhotoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { + public: + inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} + ~RespondTakePhotoResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondTakePhotoResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondTakePhotoResponse(const RespondTakePhotoResponse& from) + : RespondTakePhotoResponse(nullptr, from) {} + RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept + : RespondTakePhotoResponse() { + *this = ::std::move(from); + } + + inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& 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 RespondTakePhotoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondTakePhotoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 9; + + friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondTakePhotoResponse* 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(RespondTakePhotoResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondTakePhotoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondTakePhotoResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondTakePhotoResponse& from) { + RespondTakePhotoResponse::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(RespondTakePhotoResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; + } + protected: + explicit RespondTakePhotoResponse(::google::protobuf::Arena* arena); + RespondTakePhotoResponse(::google::protobuf::Arena* arena, const RespondTakePhotoResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondTakePhotoResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondStorageInformationResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationResponse) */ { + public: + inline RespondStorageInformationResponse() : RespondStorageInformationResponse(nullptr) {} + ~RespondStorageInformationResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondStorageInformationResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondStorageInformationResponse(const RespondStorageInformationResponse& from) + : RespondStorageInformationResponse(nullptr, from) {} + RespondStorageInformationResponse(RespondStorageInformationResponse&& from) noexcept + : RespondStorageInformationResponse() { + *this = ::std::move(from); + } + + inline RespondStorageInformationResponse& operator=(const RespondStorageInformationResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondStorageInformationResponse& operator=(RespondStorageInformationResponse&& 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 RespondStorageInformationResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondStorageInformationResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStorageInformationResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 33; + + friend void swap(RespondStorageInformationResponse& a, RespondStorageInformationResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondStorageInformationResponse* 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(RespondStorageInformationResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondStorageInformationResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondStorageInformationResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondStorageInformationResponse& from) { + RespondStorageInformationResponse::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(RespondStorageInformationResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondStorageInformationResponse"; + } + protected: + explicit RespondStorageInformationResponse(::google::protobuf::Arena* arena); + RespondStorageInformationResponse(::google::protobuf::Arena* arena, const RespondStorageInformationResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondStorageInformationResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondStorageInformationRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationRequest) */ { + public: + inline RespondStorageInformationRequest() : RespondStorageInformationRequest(nullptr) {} + ~RespondStorageInformationRequest() override; + template + explicit PROTOBUF_CONSTEXPR RespondStorageInformationRequest(::google::protobuf::internal::ConstantInitialized); + + inline RespondStorageInformationRequest(const RespondStorageInformationRequest& from) + : RespondStorageInformationRequest(nullptr, from) {} + RespondStorageInformationRequest(RespondStorageInformationRequest&& from) noexcept + : RespondStorageInformationRequest() { + *this = ::std::move(from); + } + + inline RespondStorageInformationRequest& operator=(const RespondStorageInformationRequest& from) { + CopyFrom(from); + return *this; + } + inline RespondStorageInformationRequest& operator=(RespondStorageInformationRequest&& 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 RespondStorageInformationRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RespondStorageInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStorageInformationRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 32; + + friend void swap(RespondStorageInformationRequest& a, RespondStorageInformationRequest& b) { + a.Swap(&b); + } + inline void Swap(RespondStorageInformationRequest* 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(RespondStorageInformationRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondStorageInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondStorageInformationRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondStorageInformationRequest& from) { + RespondStorageInformationRequest::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(RespondStorageInformationRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondStorageInformationRequest"; + } + protected: + explicit RespondStorageInformationRequest(::google::protobuf::Arena* arena); + RespondStorageInformationRequest(::google::protobuf::Arena* arena, const RespondStorageInformationRequest& 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 { + kStorageInformationFieldNumber = 2, + kStorageInformationFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; + bool has_storage_information() const; + void clear_storage_information() ; + const ::mavsdk::rpc::camera_server::StorageInformation& storage_information() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::StorageInformation* release_storage_information(); + ::mavsdk::rpc::camera_server::StorageInformation* mutable_storage_information(); + void set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* value); + void unsafe_arena_set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* value); + ::mavsdk::rpc::camera_server::StorageInformation* unsafe_arena_release_storage_information(); + + private: + const ::mavsdk::rpc::camera_server::StorageInformation& _internal_storage_information() const; + ::mavsdk::rpc::camera_server::StorageInformation* _internal_mutable_storage_information(); + + public: + // .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; + void clear_storage_information_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback storage_information_feedback() const; + void set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + private: + ::mavsdk::rpc::camera_server::CameraFeedback _internal_storage_information_feedback() const; + void _internal_set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::StorageInformation* storage_information_; + int storage_information_feedback_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondStopVideoStreamingResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) */ { + public: + inline RespondStopVideoStreamingResponse() : RespondStopVideoStreamingResponse(nullptr) {} + ~RespondStopVideoStreamingResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondStopVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondStopVideoStreamingResponse(const RespondStopVideoStreamingResponse& from) + : RespondStopVideoStreamingResponse(nullptr, from) {} + RespondStopVideoStreamingResponse(RespondStopVideoStreamingResponse&& from) noexcept + : RespondStopVideoStreamingResponse() { + *this = ::std::move(from); + } + + inline RespondStopVideoStreamingResponse& operator=(const RespondStopVideoStreamingResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondStopVideoStreamingResponse& operator=(RespondStopVideoStreamingResponse&& 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 RespondStopVideoStreamingResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondStopVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStopVideoStreamingResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 25; + + friend void swap(RespondStopVideoStreamingResponse& a, RespondStopVideoStreamingResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondStopVideoStreamingResponse* 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(RespondStopVideoStreamingResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondStopVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondStopVideoStreamingResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondStopVideoStreamingResponse& from) { + RespondStopVideoStreamingResponse::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(RespondStopVideoStreamingResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse"; + } + protected: + explicit RespondStopVideoStreamingResponse(::google::protobuf::Arena* arena); + RespondStopVideoStreamingResponse(::google::protobuf::Arena* arena, const RespondStopVideoStreamingResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondStopVideoStreamingResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondStopVideoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoResponse) */ { + public: + inline RespondStopVideoResponse() : RespondStopVideoResponse(nullptr) {} + ~RespondStopVideoResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondStopVideoResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondStopVideoResponse(const RespondStopVideoResponse& from) + : RespondStopVideoResponse(nullptr, from) {} + RespondStopVideoResponse(RespondStopVideoResponse&& from) noexcept + : RespondStopVideoResponse() { + *this = ::std::move(from); + } + + inline RespondStopVideoResponse& operator=(const RespondStopVideoResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondStopVideoResponse& operator=(RespondStopVideoResponse&& 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 RespondStopVideoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondStopVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStopVideoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 17; + + friend void swap(RespondStopVideoResponse& a, RespondStopVideoResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondStopVideoResponse* 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(RespondStopVideoResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondStopVideoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondStopVideoResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondStopVideoResponse& from) { + RespondStopVideoResponse::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(RespondStopVideoResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondStopVideoResponse"; + } + protected: + explicit RespondStopVideoResponse(::google::protobuf::Arena* arena); + RespondStopVideoResponse(::google::protobuf::Arena* arena, const RespondStopVideoResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondStopVideoResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondStartVideoStreamingResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) */ { + public: + inline RespondStartVideoStreamingResponse() : RespondStartVideoStreamingResponse(nullptr) {} + ~RespondStartVideoStreamingResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondStartVideoStreamingResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondStartVideoStreamingResponse(const RespondStartVideoStreamingResponse& from) + : RespondStartVideoStreamingResponse(nullptr, from) {} + RespondStartVideoStreamingResponse(RespondStartVideoStreamingResponse&& from) noexcept + : RespondStartVideoStreamingResponse() { + *this = ::std::move(from); + } + + inline RespondStartVideoStreamingResponse& operator=(const RespondStartVideoStreamingResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondStartVideoStreamingResponse& operator=(RespondStartVideoStreamingResponse&& 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 RespondStartVideoStreamingResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondStartVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStartVideoStreamingResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 21; + + friend void swap(RespondStartVideoStreamingResponse& a, RespondStartVideoStreamingResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondStartVideoStreamingResponse* 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(RespondStartVideoStreamingResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondStartVideoStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondStartVideoStreamingResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondStartVideoStreamingResponse& from) { + RespondStartVideoStreamingResponse::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(RespondStartVideoStreamingResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse"; + } + protected: + explicit RespondStartVideoStreamingResponse(::google::protobuf::Arena* arena); + RespondStartVideoStreamingResponse(::google::protobuf::Arena* arena, const RespondStartVideoStreamingResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondStartVideoStreamingResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondStartVideoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoResponse) */ { + public: + inline RespondStartVideoResponse() : RespondStartVideoResponse(nullptr) {} + ~RespondStartVideoResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondStartVideoResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondStartVideoResponse(const RespondStartVideoResponse& from) + : RespondStartVideoResponse(nullptr, from) {} + RespondStartVideoResponse(RespondStartVideoResponse&& from) noexcept + : RespondStartVideoResponse() { + *this = ::std::move(from); + } + + inline RespondStartVideoResponse& operator=(const RespondStartVideoResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondStartVideoResponse& operator=(RespondStartVideoResponse&& 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 RespondStartVideoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondStartVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStartVideoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 13; + + friend void swap(RespondStartVideoResponse& a, RespondStartVideoResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondStartVideoResponse* 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(RespondStartVideoResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondStartVideoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondStartVideoResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondStartVideoResponse& from) { + RespondStartVideoResponse::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(RespondStartVideoResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondStartVideoResponse"; + } + protected: + explicit RespondStartVideoResponse(::google::protobuf::Arena* arena); + RespondStartVideoResponse(::google::protobuf::Arena* arena, const RespondStartVideoResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondStartVideoResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondSetModeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondSetModeResponse) */ { + public: + inline RespondSetModeResponse() : RespondSetModeResponse(nullptr) {} + ~RespondSetModeResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondSetModeResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondSetModeResponse(const RespondSetModeResponse& from) + : RespondSetModeResponse(nullptr, from) {} + RespondSetModeResponse(RespondSetModeResponse&& from) noexcept + : RespondSetModeResponse() { + *this = ::std::move(from); + } + + inline RespondSetModeResponse& operator=(const RespondSetModeResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondSetModeResponse& operator=(RespondSetModeResponse&& 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 RespondSetModeResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondSetModeResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondSetModeResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 29; + + friend void swap(RespondSetModeResponse& a, RespondSetModeResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondSetModeResponse* 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(RespondSetModeResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondSetModeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondSetModeResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondSetModeResponse& from) { + RespondSetModeResponse::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(RespondSetModeResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondSetModeResponse"; + } + protected: + explicit RespondSetModeResponse(::google::protobuf::Arena* arena); + RespondSetModeResponse(::google::protobuf::Arena* arena, const RespondSetModeResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondSetModeResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondResetSettingsResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondResetSettingsResponse) */ { + public: + inline RespondResetSettingsResponse() : RespondResetSettingsResponse(nullptr) {} + ~RespondResetSettingsResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondResetSettingsResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondResetSettingsResponse(const RespondResetSettingsResponse& from) + : RespondResetSettingsResponse(nullptr, from) {} + RespondResetSettingsResponse(RespondResetSettingsResponse&& from) noexcept + : RespondResetSettingsResponse() { + *this = ::std::move(from); + } + + inline RespondResetSettingsResponse& operator=(const RespondResetSettingsResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondResetSettingsResponse& operator=(RespondResetSettingsResponse&& 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 RespondResetSettingsResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondResetSettingsResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondResetSettingsResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 45; + + friend void swap(RespondResetSettingsResponse& a, RespondResetSettingsResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondResetSettingsResponse* 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(RespondResetSettingsResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondResetSettingsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondResetSettingsResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondResetSettingsResponse& from) { + RespondResetSettingsResponse::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(RespondResetSettingsResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondResetSettingsResponse"; + } + protected: + explicit RespondResetSettingsResponse(::google::protobuf::Arena* arena); + RespondResetSettingsResponse(::google::protobuf::Arena* arena, const RespondResetSettingsResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondResetSettingsResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondFormatStorageResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondFormatStorageResponse) */ { + public: + inline RespondFormatStorageResponse() : RespondFormatStorageResponse(nullptr) {} + ~RespondFormatStorageResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondFormatStorageResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondFormatStorageResponse(const RespondFormatStorageResponse& from) + : RespondFormatStorageResponse(nullptr, from) {} + RespondFormatStorageResponse(RespondFormatStorageResponse&& from) noexcept + : RespondFormatStorageResponse() { + *this = ::std::move(from); + } + + inline RespondFormatStorageResponse& operator=(const RespondFormatStorageResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondFormatStorageResponse& operator=(RespondFormatStorageResponse&& 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 RespondFormatStorageResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondFormatStorageResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondFormatStorageResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 41; + + friend void swap(RespondFormatStorageResponse& a, RespondFormatStorageResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondFormatStorageResponse* 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(RespondFormatStorageResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondFormatStorageResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondFormatStorageResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondFormatStorageResponse& from) { + RespondFormatStorageResponse::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(RespondFormatStorageResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondFormatStorageResponse"; + } + protected: + explicit RespondFormatStorageResponse(::google::protobuf::Arena* arena); + RespondFormatStorageResponse(::google::protobuf::Arena* arena, const RespondFormatStorageResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondFormatStorageResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondCaptureStatusResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) */ { + public: + inline RespondCaptureStatusResponse() : RespondCaptureStatusResponse(nullptr) {} + ~RespondCaptureStatusResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondCaptureStatusResponse(::google::protobuf::internal::ConstantInitialized); + + inline RespondCaptureStatusResponse(const RespondCaptureStatusResponse& from) + : RespondCaptureStatusResponse(nullptr, from) {} + RespondCaptureStatusResponse(RespondCaptureStatusResponse&& from) noexcept + : RespondCaptureStatusResponse() { + *this = ::std::move(from); + } + + inline RespondCaptureStatusResponse& operator=(const RespondCaptureStatusResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondCaptureStatusResponse& operator=(RespondCaptureStatusResponse&& 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 RespondCaptureStatusResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondCaptureStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondCaptureStatusResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 37; + + friend void swap(RespondCaptureStatusResponse& a, RespondCaptureStatusResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondCaptureStatusResponse* 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(RespondCaptureStatusResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondCaptureStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondCaptureStatusResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondCaptureStatusResponse& from) { + RespondCaptureStatusResponse::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(RespondCaptureStatusResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondCaptureStatusResponse"; + } + protected: + explicit RespondCaptureStatusResponse(::google::protobuf::Arena* arena); + RespondCaptureStatusResponse(::google::protobuf::Arena* arena, const RespondCaptureStatusResponse& 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 { + kCameraServerResultFieldNumber = 1, + }; + // .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::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.RespondCaptureStatusResponse) + 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondCaptureStatusRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) */ { + public: + inline RespondCaptureStatusRequest() : RespondCaptureStatusRequest(nullptr) {} + ~RespondCaptureStatusRequest() override; + template + explicit PROTOBUF_CONSTEXPR RespondCaptureStatusRequest(::google::protobuf::internal::ConstantInitialized); + + inline RespondCaptureStatusRequest(const RespondCaptureStatusRequest& from) + : RespondCaptureStatusRequest(nullptr, from) {} + RespondCaptureStatusRequest(RespondCaptureStatusRequest&& from) noexcept + : RespondCaptureStatusRequest() { + *this = ::std::move(from); + } + + inline RespondCaptureStatusRequest& operator=(const RespondCaptureStatusRequest& from) { + CopyFrom(from); + return *this; + } + inline RespondCaptureStatusRequest& operator=(RespondCaptureStatusRequest&& 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 RespondCaptureStatusRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RespondCaptureStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondCaptureStatusRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 36; + + friend void swap(RespondCaptureStatusRequest& a, RespondCaptureStatusRequest& b) { + a.Swap(&b); + } + inline void Swap(RespondCaptureStatusRequest* 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(RespondCaptureStatusRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondCaptureStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondCaptureStatusRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondCaptureStatusRequest& from) { + RespondCaptureStatusRequest::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(RespondCaptureStatusRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondCaptureStatusRequest"; + } + protected: + explicit RespondCaptureStatusRequest(::google::protobuf::Arena* arena); + RespondCaptureStatusRequest(::google::protobuf::Arena* arena, const RespondCaptureStatusRequest& 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 { + kCaptureStatusFieldNumber = 2, + kCaptureStatusFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; + bool has_capture_status() const; + void clear_capture_status() ; + const ::mavsdk::rpc::camera_server::CaptureStatus& capture_status() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureStatus* release_capture_status(); + ::mavsdk::rpc::camera_server::CaptureStatus* mutable_capture_status(); + void set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* value); + void unsafe_arena_set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* value); + ::mavsdk::rpc::camera_server::CaptureStatus* unsafe_arena_release_capture_status(); + + private: + const ::mavsdk::rpc::camera_server::CaptureStatus& _internal_capture_status() const; + ::mavsdk::rpc::camera_server::CaptureStatus* _internal_mutable_capture_status(); + + public: + // .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; + void clear_capture_status_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback capture_status_feedback() const; + void set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + private: + ::mavsdk::rpc::camera_server::CameraFeedback _internal_capture_status_feedback() const; + void _internal_set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CaptureStatus* capture_status_; + int capture_status_feedback_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class CaptureInfo final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureInfo) */ { + public: + inline CaptureInfo() : CaptureInfo(nullptr) {} + ~CaptureInfo() override; + template + explicit PROTOBUF_CONSTEXPR CaptureInfo(::google::protobuf::internal::ConstantInitialized); + + inline CaptureInfo(const CaptureInfo& from) + : CaptureInfo(nullptr, from) {} + CaptureInfo(CaptureInfo&& from) noexcept + : CaptureInfo() { + *this = ::std::move(from); + } + + inline CaptureInfo& operator=(const CaptureInfo& from) { + CopyFrom(from); + return *this; + } + inline CaptureInfo& operator=(CaptureInfo&& 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 CaptureInfo& default_instance() { + return *internal_default_instance(); + } + static inline const CaptureInfo* internal_default_instance() { + return reinterpret_cast( + &_CaptureInfo_default_instance_); + } + static constexpr int kIndexInFileMessages = + 66; + + friend void swap(CaptureInfo& a, CaptureInfo& b) { + a.Swap(&b); + } + inline void Swap(CaptureInfo* 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(CaptureInfo* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + CaptureInfo* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const CaptureInfo& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const CaptureInfo& from) { + CaptureInfo::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(CaptureInfo* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.CaptureInfo"; + } + protected: + explicit CaptureInfo(::google::protobuf::Arena* arena); + CaptureInfo(::google::protobuf::Arena* arena, const CaptureInfo& 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 { + kFileUrlFieldNumber = 6, + kPositionFieldNumber = 1, + kAttitudeQuaternionFieldNumber = 2, + kTimeUtcUsFieldNumber = 3, + kIsSuccessFieldNumber = 4, + kIndexFieldNumber = 5, + }; + // string file_url = 6; + void clear_file_url() ; + const std::string& file_url() const; + template + void set_file_url(Arg_&& arg, Args_... args); + std::string* mutable_file_url(); + PROTOBUF_NODISCARD std::string* release_file_url(); + void set_allocated_file_url(std::string* value); + + private: + const std::string& _internal_file_url() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_file_url( + const std::string& value); + std::string* _internal_mutable_file_url(); + + public: + // .mavsdk.rpc.camera_server.Position position = 1; + bool has_position() const; + void clear_position() ; + const ::mavsdk::rpc::camera_server::Position& position() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Position* release_position(); + ::mavsdk::rpc::camera_server::Position* mutable_position(); + void set_allocated_position(::mavsdk::rpc::camera_server::Position* value); + void unsafe_arena_set_allocated_position(::mavsdk::rpc::camera_server::Position* value); + ::mavsdk::rpc::camera_server::Position* unsafe_arena_release_position(); + + private: + const ::mavsdk::rpc::camera_server::Position& _internal_position() const; + ::mavsdk::rpc::camera_server::Position* _internal_mutable_position(); + + public: + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + bool has_attitude_quaternion() const; + void clear_attitude_quaternion() ; + const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Quaternion* release_attitude_quaternion(); + ::mavsdk::rpc::camera_server::Quaternion* mutable_attitude_quaternion(); + void set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* value); + void unsafe_arena_set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* value); + ::mavsdk::rpc::camera_server::Quaternion* unsafe_arena_release_attitude_quaternion(); + + private: + const ::mavsdk::rpc::camera_server::Quaternion& _internal_attitude_quaternion() const; + ::mavsdk::rpc::camera_server::Quaternion* _internal_mutable_attitude_quaternion(); + + public: + // uint64 time_utc_us = 3; + void clear_time_utc_us() ; + ::uint64_t time_utc_us() const; + void set_time_utc_us(::uint64_t value); + + private: + ::uint64_t _internal_time_utc_us() const; + void _internal_set_time_utc_us(::uint64_t value); + + public: + // bool is_success = 4; + void clear_is_success() ; + bool is_success() const; + void set_is_success(bool value); + + private: + bool _internal_is_success() const; + void _internal_set_is_success(bool value); + + public: + // int32 index = 5; + void clear_index() ; + ::int32_t index() const; + void set_index(::int32_t value); + + private: + ::int32_t _internal_index() const; + void _internal_set_index(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureInfo) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 3, 6, 2, + 53, 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::google::protobuf::internal::ArenaStringPtr file_url_; + ::mavsdk::rpc::camera_server::Position* position_; + ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion_; + ::uint64_t time_utc_us_; + bool is_success_; + ::int32_t index_; + 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: + inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} + ~RespondTakePhotoRequest() override; + template + explicit PROTOBUF_CONSTEXPR RespondTakePhotoRequest(::google::protobuf::internal::ConstantInitialized); + + inline RespondTakePhotoRequest(const RespondTakePhotoRequest& from) + : RespondTakePhotoRequest(nullptr, from) {} + RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept + : RespondTakePhotoRequest() { + *this = ::std::move(from); + } + + inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { + CopyFrom(from); + return *this; + } + inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& 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 RespondTakePhotoRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RespondTakePhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 8; + + friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { + a.Swap(&b); + } + inline void Swap(RespondTakePhotoRequest* 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(RespondTakePhotoRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondTakePhotoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RespondTakePhotoRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RespondTakePhotoRequest& from) { + RespondTakePhotoRequest::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(RespondTakePhotoRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; + } + protected: + explicit RespondTakePhotoRequest(::google::protobuf::Arena* arena); + RespondTakePhotoRequest(::google::protobuf::Arena* arena, const RespondTakePhotoRequest& 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 { + kCaptureInfoFieldNumber = 2, + kTakePhotoFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + bool has_capture_info() const; + void clear_capture_info() ; + const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureInfo* release_capture_info(); + ::mavsdk::rpc::camera_server::CaptureInfo* mutable_capture_info(); + void set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* value); + void unsafe_arena_set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* value); + ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); + + private: + const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; + ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); + + public: + // .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; + void clear_take_photo_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback take_photo_feedback() const; + void set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + private: + ::mavsdk::rpc::camera_server::CameraFeedback _internal_take_photo_feedback() const; + void _internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 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::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info_; + int take_photo_feedback_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; + +// =================================================================== + + + + +// =================================================================== + + +#ifdef __GNUC__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ------------------------------------------------------------------- // SetInformationRequest -// .mavsdk.rpc.camera_server.Information information = 1; -inline bool SetInformationRequest::has_information() const { +// .mavsdk.rpc.camera_server.Information information = 1; +inline bool SetInformationRequest::has_information() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.information_ != nullptr); + return value; +} +inline void SetInformationRequest::clear_information() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.information_ != nullptr) _impl_.information_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::_internal_information() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::camera_server::Information* p = _impl_.information_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_Information_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::information() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInformationRequest.information) + return _internal_information(); +} +inline void SetInformationRequest::unsafe_arena_set_allocated_information(::mavsdk::rpc::camera_server::Information* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.information_); + } + _impl_.information_ = reinterpret_cast<::mavsdk::rpc::camera_server::Information*>(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.SetInformationRequest.information) +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::release_information() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::Information* released = _impl_.information_; + _impl_.information_ = 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::Information* SetInformationRequest::unsafe_arena_release_information() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationRequest.information) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::Information* temp = _impl_.information_; + _impl_.information_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::_internal_mutable_information() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.information_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(GetArena()); + _impl_.information_ = reinterpret_cast<::mavsdk::rpc::camera_server::Information*>(p); + } + return _impl_.information_; +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::mutable_information() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::camera_server::Information* _msg = _internal_mutable_information(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInformationRequest.information) + return _msg; +} +inline void SetInformationRequest::set_allocated_information(::mavsdk::rpc::camera_server::Information* 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::Information*>(_impl_.information_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::Information*>(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_.information_ = reinterpret_cast<::mavsdk::rpc::camera_server::Information*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationRequest.information) +} + +// ------------------------------------------------------------------- + +// SetInformationResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool SetInformationResponse::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 SetInformationResponse::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& SetInformationResponse::_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& SetInformationResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void SetInformationResponse::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_); + } + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(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.SetInformationResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::release_camera_server_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* released = _impl_.camera_server_result_; + _impl_.camera_server_result_ = 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::CameraServerResult* SetInformationResponse::unsafe_arena_release_camera_server_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationResponse.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* SetInformationResponse::_internal_mutable_camera_server_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArena()); + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(p); + } + return _impl_.camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::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.SetInformationResponse.camera_server_result) + return _msg; +} +inline void SetInformationResponse::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) { + delete reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(_impl_.camera_server_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(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_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + +// SetVideoStreamingRequest + +// .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_.information_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.video_streaming_ != nullptr); return value; } -inline void SetInformationRequest::clear_information() { +inline void SetVideoStreamingRequest::clear_video_streaming() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.information_ != nullptr) _impl_.information_->Clear(); + if (_impl_.video_streaming_ != nullptr) _impl_.video_streaming_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::_internal_information() const { +inline const ::mavsdk::rpc::camera_server::VideoStreaming& SetVideoStreamingRequest::_internal_video_streaming() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::camera_server::Information* p = _impl_.information_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_Information_default_instance_); + const ::mavsdk::rpc::camera_server::VideoStreaming* p = _impl_.video_streaming_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_VideoStreaming_default_instance_); } -inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::information() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInformationRequest.information) - return _internal_information(); +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 void SetInformationRequest::unsafe_arena_set_allocated_information(::mavsdk::rpc::camera_server::Information* value) { +inline void SetVideoStreamingRequest::unsafe_arena_set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.information_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.video_streaming_); } - _impl_.information_ = reinterpret_cast<::mavsdk::rpc::camera_server::Information*>(value); + _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.SetInformationRequest.information) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) } -inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::release_information() { +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::Information* released = _impl_.information_; - _impl_.information_ = nullptr; + ::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); @@ -10343,38 +13259,38 @@ inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::release #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::unsafe_arena_release_information() { +inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::unsafe_arena_release_video_streaming() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationRequest.information) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::Information* temp = _impl_.information_; - _impl_.information_ = nullptr; + ::mavsdk::rpc::camera_server::VideoStreaming* temp = _impl_.video_streaming_; + _impl_.video_streaming_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::_internal_mutable_information() { +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_.information_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(GetArena()); - _impl_.information_ = reinterpret_cast<::mavsdk::rpc::camera_server::Information*>(p); + 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_.information_; + return _impl_.video_streaming_; } -inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::mutable_information() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::camera_server::Information* _msg = _internal_mutable_information(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInformationRequest.information) +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 void SetInformationRequest::set_allocated_information(::mavsdk::rpc::camera_server::Information* value) { +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::Information*>(_impl_.information_); + 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::Information*>(value)->GetArena(); + ::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); } @@ -10383,35 +13299,162 @@ inline void SetInformationRequest::set_allocated_information(::mavsdk::rpc::came _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.information_ = reinterpret_cast<::mavsdk::rpc::camera_server::Information*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationRequest.information) + _impl_.video_streaming_ = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreaming*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) +} + +// ------------------------------------------------------------------- + +// SetVideoStreamingResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool SetVideoStreamingResponse::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() { + 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 { + 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) + return _internal_camera_server_result(); +} +inline void SetVideoStreamingResponse::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_); + } + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(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.SetVideoStreamingResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::release_camera_server_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* released = _impl_.camera_server_result_; + _impl_.camera_server_result_ = 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::CameraServerResult* SetVideoStreamingResponse::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) + + _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() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArena()); + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(p); + } + return _impl_.camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::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) + return _msg; +} +inline void SetVideoStreamingResponse::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) { + delete reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(_impl_.camera_server_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(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_.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) +} + +// ------------------------------------------------------------------- + +// SetInProgressRequest + +// bool in_progress = 1; +inline void SetInProgressRequest::clear_in_progress() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.in_progress_ = false; +} +inline bool SetInProgressRequest::in_progress() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressRequest.in_progress) + return _internal_in_progress(); +} +inline void SetInProgressRequest::set_in_progress(bool value) { + _internal_set_in_progress(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetInProgressRequest.in_progress) +} +inline bool SetInProgressRequest::_internal_in_progress() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.in_progress_; +} +inline void SetInProgressRequest::_internal_set_in_progress(bool value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.in_progress_ = value; } // ------------------------------------------------------------------- -// SetInformationResponse +// SetInProgressResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool SetInformationResponse::has_camera_server_result() const { +inline bool SetInProgressResponse::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 SetInformationResponse::clear_camera_server_result() { +inline void SetInProgressResponse::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& SetInformationResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInProgressResponse::_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& SetInformationResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInProgressResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) return _internal_camera_server_result(); } -inline void SetInformationResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void SetInProgressResponse::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_); @@ -10422,9 +13465,9 @@ inline void SetInformationResponse::unsafe_arena_set_allocated_camera_server_res } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -10443,16 +13486,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse: #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInProgressResponse.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* SetInformationResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -10461,12 +13504,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse: } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::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.SetInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) return _msg; } -inline void SetInformationResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void SetInProgressResponse::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) { @@ -10484,52 +13527,106 @@ inline void SetInformationResponse::set_allocated_camera_server_result(::mavsdk: } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) } // ------------------------------------------------------------------- -// SetVideoStreamingRequest +// SubscribeTakePhotoRequest -// .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; -inline bool SetVideoStreamingRequest::has_video_streaming() const { +// ------------------------------------------------------------------- + +// TakePhotoResponse + +// int32 index = 1; +inline void TakePhotoResponse::clear_index() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.index_ = 0; +} +inline ::int32_t TakePhotoResponse::index() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.TakePhotoResponse.index) + return _internal_index(); +} +inline void TakePhotoResponse::set_index(::int32_t value) { + _internal_set_index(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.TakePhotoResponse.index) +} +inline ::int32_t TakePhotoResponse::_internal_index() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.index_; +} +inline void TakePhotoResponse::_internal_set_index(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.index_ = value; +} + +// ------------------------------------------------------------------- + +// RespondTakePhotoRequest + +// .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; +inline void RespondTakePhotoRequest::clear_take_photo_feedback() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.take_photo_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondTakePhotoRequest::take_photo_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.take_photo_feedback) + return _internal_take_photo_feedback(); +} +inline void RespondTakePhotoRequest::set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_take_photo_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondTakePhotoRequest.take_photo_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondTakePhotoRequest::_internal_take_photo_feedback() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.take_photo_feedback_); +} +inline void RespondTakePhotoRequest::_internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.take_photo_feedback_ = value; +} + +// .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; +inline bool RespondTakePhotoRequest::has_capture_info() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.video_streaming_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.capture_info_ != nullptr); return value; } -inline void SetVideoStreamingRequest::clear_video_streaming() { +inline void RespondTakePhotoRequest::clear_capture_info() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.video_streaming_ != nullptr) _impl_.video_streaming_->Clear(); + if (_impl_.capture_info_ != nullptr) _impl_.capture_info_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::VideoStreaming& SetVideoStreamingRequest::_internal_video_streaming() const { +inline const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::_internal_capture_info() 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_); + const ::mavsdk::rpc::camera_server::CaptureInfo* p = _impl_.capture_info_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_); } -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 const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::capture_info() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) + return _internal_capture_info(); } -inline void SetVideoStreamingRequest::unsafe_arena_set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* value) { +inline void RespondTakePhotoRequest::unsafe_arena_set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.video_streaming_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.capture_info_); } - _impl_.video_streaming_ = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreaming*>(value); + _impl_.capture_info_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(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) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) } -inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::release_video_streaming() { +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::release_capture_info() { 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; + ::mavsdk::rpc::camera_server::CaptureInfo* released = _impl_.capture_info_; + _impl_.capture_info_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -10543,38 +13640,38 @@ inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::r #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::unsafe_arena_release_video_streaming() { +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::unsafe_arena_release_capture_info() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::VideoStreaming* temp = _impl_.video_streaming_; - _impl_.video_streaming_ = nullptr; + ::mavsdk::rpc::camera_server::CaptureInfo* temp = _impl_.capture_info_; + _impl_.capture_info_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::_internal_mutable_video_streaming() { +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::_internal_mutable_capture_info() { 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); + if (_impl_.capture_info_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(GetArena()); + _impl_.capture_info_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(p); } - return _impl_.video_streaming_; + return _impl_.capture_info_; } -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) +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::mutable_capture_info() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::camera_server::CaptureInfo* _msg = _internal_mutable_capture_info(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) return _msg; } -inline void SetVideoStreamingRequest::set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* value) { +inline void RespondTakePhotoRequest::set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* 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_); + delete reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(_impl_.capture_info_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::VideoStreaming*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } @@ -10583,35 +13680,35 @@ inline void SetVideoStreamingRequest::set_allocated_video_streaming(::mavsdk::rp _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) + _impl_.capture_info_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) } // ------------------------------------------------------------------- -// SetVideoStreamingResponse +// RespondTakePhotoResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool SetVideoStreamingResponse::has_camera_server_result() const { +inline bool RespondTakePhotoResponse::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 RespondTakePhotoResponse::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& RespondTakePhotoResponse::_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& RespondTakePhotoResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoResponse.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 RespondTakePhotoResponse::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 +13719,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.RespondTakePhotoResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -10643,16 +13740,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* RespondTakePhotoResponse::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.RespondTakePhotoResponse.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* RespondTakePhotoResponse::_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 +13758,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* RespondTakePhotoResponse::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.RespondTakePhotoResponse.camera_server_result) return _msg; } -inline void SetVideoStreamingResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondTakePhotoResponse::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,61 +13781,92 @@ 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.RespondTakePhotoResponse.camera_server_result) } // ------------------------------------------------------------------- -// SetInProgressRequest +// SubscribeStartVideoRequest -// bool in_progress = 1; -inline void SetInProgressRequest::clear_in_progress() { +// ------------------------------------------------------------------- + +// StartVideoResponse + +// int32 stream_id = 1; +inline void StartVideoResponse::clear_stream_id() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.in_progress_ = false; + _impl_.stream_id_ = 0; } -inline bool SetInProgressRequest::in_progress() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressRequest.in_progress) - return _internal_in_progress(); +inline ::int32_t StartVideoResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) + return _internal_stream_id(); } -inline void SetInProgressRequest::set_in_progress(bool value) { - _internal_set_in_progress(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetInProgressRequest.in_progress) +inline void StartVideoResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) +} +inline ::int32_t StartVideoResponse::_internal_stream_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.stream_id_; +} +inline void StartVideoResponse::_internal_set_stream_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.stream_id_ = value; +} + +// ------------------------------------------------------------------- + +// RespondStartVideoRequest + +// .mavsdk.rpc.camera_server.CameraFeedback start_video_feedback = 1; +inline void RespondStartVideoRequest::clear_start_video_feedback() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.start_video_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoRequest::start_video_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoRequest.start_video_feedback) + return _internal_start_video_feedback(); +} +inline void RespondStartVideoRequest::set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_start_video_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStartVideoRequest.start_video_feedback) } -inline bool SetInProgressRequest::_internal_in_progress() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoRequest::_internal_start_video_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.in_progress_; + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.start_video_feedback_); } -inline void SetInProgressRequest::_internal_set_in_progress(bool value) { +inline void RespondStartVideoRequest::_internal_set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.in_progress_ = value; + _impl_.start_video_feedback_ = value; } // ------------------------------------------------------------------- -// SetInProgressResponse +// RespondStartVideoResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool SetInProgressResponse::has_camera_server_result() const { +inline bool RespondStartVideoResponse::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 SetInProgressResponse::clear_camera_server_result() { +inline void RespondStartVideoResponse::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& SetInProgressResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoResponse::_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& SetInProgressResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) return _internal_camera_server_result(); } -inline void SetInProgressResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStartVideoResponse::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_); @@ -10749,9 +13877,9 @@ inline void SetInProgressResponse::unsafe_arena_set_allocated_camera_server_resu } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -10770,16 +13898,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse:: #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStartVideoResponse.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* SetInProgressResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -10788,12 +13916,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse:: } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::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.SetInProgressResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) return _msg; } -inline void SetInProgressResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStartVideoResponse::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) { @@ -10811,106 +13939,110 @@ inline void SetInProgressResponse::set_allocated_camera_server_result(::mavsdk:: } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeTakePhotoRequest +// SubscribeStopVideoRequest // ------------------------------------------------------------------- -// TakePhotoResponse +// StopVideoResponse -// int32 index = 1; -inline void TakePhotoResponse::clear_index() { +// int32 stream_id = 1; +inline void StopVideoResponse::clear_stream_id() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.index_ = 0; + _impl_.stream_id_ = 0; } -inline ::int32_t TakePhotoResponse::index() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.TakePhotoResponse.index) - return _internal_index(); +inline ::int32_t StopVideoResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) + return _internal_stream_id(); } -inline void TakePhotoResponse::set_index(::int32_t value) { - _internal_set_index(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.TakePhotoResponse.index) +inline void StopVideoResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) } -inline ::int32_t TakePhotoResponse::_internal_index() const { +inline ::int32_t StopVideoResponse::_internal_stream_id() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.index_; + return _impl_.stream_id_; } -inline void TakePhotoResponse::_internal_set_index(::int32_t value) { +inline void StopVideoResponse::_internal_set_stream_id(::int32_t value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.index_ = value; + _impl_.stream_id_ = value; } // ------------------------------------------------------------------- -// RespondTakePhotoRequest +// RespondStopVideoRequest -// .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; -inline void RespondTakePhotoRequest::clear_take_photo_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; +inline void RespondStopVideoRequest::clear_stop_video_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.take_photo_feedback_ = 0; + _impl_.stop_video_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondTakePhotoRequest::take_photo_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.take_photo_feedback) - return _internal_take_photo_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoRequest::stop_video_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoRequest.stop_video_feedback) + return _internal_stop_video_feedback(); } -inline void RespondTakePhotoRequest::set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_take_photo_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondTakePhotoRequest.take_photo_feedback) +inline void RespondStopVideoRequest::set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_stop_video_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStopVideoRequest.stop_video_feedback) } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondTakePhotoRequest::_internal_take_photo_feedback() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoRequest::_internal_stop_video_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.take_photo_feedback_); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.stop_video_feedback_); } -inline void RespondTakePhotoRequest::_internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondStopVideoRequest::_internal_set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.take_photo_feedback_ = value; + _impl_.stop_video_feedback_ = value; } -// .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; -inline bool RespondTakePhotoRequest::has_capture_info() const { +// ------------------------------------------------------------------- + +// RespondStopVideoResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondStopVideoResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.capture_info_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void RespondTakePhotoRequest::clear_capture_info() { +inline void RespondStopVideoResponse::clear_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.capture_info_ != nullptr) _impl_.capture_info_->Clear(); + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::_internal_capture_info() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStopVideoResponse::_internal_camera_server_result() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::camera_server::CaptureInfo* p = _impl_.capture_info_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_); + 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::CaptureInfo& RespondTakePhotoRequest::capture_info() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) - return _internal_capture_info(); +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStopVideoResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) + return _internal_camera_server_result(); } -inline void RespondTakePhotoRequest::unsafe_arena_set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* value) { +inline void RespondStopVideoResponse::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_.capture_info_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.camera_server_result_); } - _impl_.capture_info_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(value); + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(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.RespondTakePhotoRequest.capture_info) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::release_capture_info() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::CaptureInfo* released = _impl_.capture_info_; - _impl_.capture_info_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* released = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -10924,38 +14056,38 @@ inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::relea #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::unsafe_arena_release_capture_info() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::CaptureInfo* temp = _impl_.capture_info_; - _impl_.capture_info_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::_internal_mutable_capture_info() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.capture_info_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(GetArena()); - _impl_.capture_info_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(p); + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArena()); + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(p); } - return _impl_.capture_info_; + return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::mutable_capture_info() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::camera_server::CaptureInfo* _msg = _internal_mutable_capture_info(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::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.RespondStopVideoResponse.camera_server_result) return _msg; } -inline void RespondTakePhotoRequest::set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* value) { +inline void RespondStopVideoResponse::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) { - delete reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(_impl_.capture_info_); + delete reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(_impl_.camera_server_result_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } @@ -10964,35 +14096,93 @@ inline void RespondTakePhotoRequest::set_allocated_capture_info(::mavsdk::rpc::c _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.capture_info_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureInfo*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) } // ------------------------------------------------------------------- -// RespondTakePhotoResponse +// SubscribeStartVideoStreamingRequest + +// ------------------------------------------------------------------- + +// StartVideoStreamingResponse + +// int32 stream_id = 1; +inline void StartVideoStreamingResponse::clear_stream_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.stream_id_ = 0; +} +inline ::int32_t StartVideoStreamingResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) + return _internal_stream_id(); +} +inline void StartVideoStreamingResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) +} +inline ::int32_t StartVideoStreamingResponse::_internal_stream_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.stream_id_; +} +inline void StartVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.stream_id_ = value; +} + +// ------------------------------------------------------------------- + +// RespondStartVideoStreamingRequest + +// .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; +inline void RespondStartVideoStreamingRequest::clear_start_video_streaming_feedback() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.start_video_streaming_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoStreamingRequest::start_video_streaming_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest.start_video_streaming_feedback) + return _internal_start_video_streaming_feedback(); +} +inline void RespondStartVideoStreamingRequest::set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_start_video_streaming_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest.start_video_streaming_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoStreamingRequest::_internal_start_video_streaming_feedback() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.start_video_streaming_feedback_); +} +inline void RespondStartVideoStreamingRequest::_internal_set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.start_video_streaming_feedback_ = value; +} + +// ------------------------------------------------------------------- + +// RespondStartVideoStreamingResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondTakePhotoResponse::has_camera_server_result() const { +inline bool RespondStartVideoStreamingResponse::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 RespondTakePhotoResponse::clear_camera_server_result() { +inline void RespondStartVideoStreamingResponse::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& RespondTakePhotoResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoStreamingResponse::_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& RespondTakePhotoResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoStreamingResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondTakePhotoResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStartVideoStreamingResponse::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_); @@ -11003,9 +14193,9 @@ inline void RespondTakePhotoResponse::unsafe_arena_set_allocated_camera_server_r } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -11024,16 +14214,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoRespons #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.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* RespondTakePhotoResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -11042,12 +14232,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoRespons } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::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.RespondTakePhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) return _msg; } -inline void RespondTakePhotoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStartVideoStreamingResponse::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) { @@ -11065,35 +14255,35 @@ inline void RespondTakePhotoResponse::set_allocated_camera_server_result(::mavsd } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeStartVideoRequest +// SubscribeStopVideoStreamingRequest // ------------------------------------------------------------------- -// StartVideoResponse +// StopVideoStreamingResponse // int32 stream_id = 1; -inline void StartVideoResponse::clear_stream_id() { +inline void StopVideoStreamingResponse::clear_stream_id() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.stream_id_ = 0; } -inline ::int32_t StartVideoResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) +inline ::int32_t StopVideoStreamingResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) return _internal_stream_id(); } -inline void StartVideoResponse::set_stream_id(::int32_t value) { +inline void StopVideoStreamingResponse::set_stream_id(::int32_t value) { _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) } -inline ::int32_t StartVideoResponse::_internal_stream_id() const { +inline ::int32_t StopVideoStreamingResponse::_internal_stream_id() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); return _impl_.stream_id_; } -inline void StartVideoResponse::_internal_set_stream_id(::int32_t value) { +inline void StopVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; _impl_.stream_id_ = value; @@ -11101,56 +14291,56 @@ inline void StartVideoResponse::_internal_set_stream_id(::int32_t value) { // ------------------------------------------------------------------- -// RespondStartVideoRequest +// RespondStopVideoStreamingRequest -// .mavsdk.rpc.camera_server.CameraFeedback start_video_feedback = 1; -inline void RespondStartVideoRequest::clear_start_video_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; +inline void RespondStopVideoStreamingRequest::clear_stop_video_streaming_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.start_video_feedback_ = 0; + _impl_.stop_video_streaming_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoRequest::start_video_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoRequest.start_video_feedback) - return _internal_start_video_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoStreamingRequest::stop_video_streaming_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest.stop_video_streaming_feedback) + return _internal_stop_video_streaming_feedback(); } -inline void RespondStartVideoRequest::set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_start_video_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStartVideoRequest.start_video_feedback) +inline void RespondStopVideoStreamingRequest::set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_stop_video_streaming_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest.stop_video_streaming_feedback) } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoRequest::_internal_start_video_feedback() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoStreamingRequest::_internal_stop_video_streaming_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.start_video_feedback_); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.stop_video_streaming_feedback_); } -inline void RespondStartVideoRequest::_internal_set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondStopVideoStreamingRequest::_internal_set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.start_video_feedback_ = value; + _impl_.stop_video_streaming_feedback_ = value; } // ------------------------------------------------------------------- -// RespondStartVideoResponse +// RespondStopVideoStreamingResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondStartVideoResponse::has_camera_server_result() const { +inline bool RespondStopVideoStreamingResponse::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 RespondStartVideoResponse::clear_camera_server_result() { +inline void RespondStopVideoStreamingResponse::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& RespondStartVideoResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStopVideoStreamingResponse::_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& RespondStartVideoResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStopVideoStreamingResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondStartVideoResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStopVideoStreamingResponse::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_); @@ -11161,9 +14351,9 @@ inline void RespondStartVideoResponse::unsafe_arena_set_allocated_camera_server_ } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -11182,16 +14372,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoRespon #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.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* RespondStartVideoResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -11200,12 +14390,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoRespon } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::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.RespondStartVideoResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) return _msg; } -inline void RespondStartVideoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStopVideoStreamingResponse::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) { @@ -11223,92 +14413,92 @@ inline void RespondStartVideoResponse::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.RespondStartVideoResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeStopVideoRequest +// SubscribeSetModeRequest // ------------------------------------------------------------------- -// StopVideoResponse +// SetModeResponse -// int32 stream_id = 1; -inline void StopVideoResponse::clear_stream_id() { +// .mavsdk.rpc.camera_server.Mode mode = 1; +inline void SetModeResponse::clear_mode() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.stream_id_ = 0; + _impl_.mode_ = 0; } -inline ::int32_t StopVideoResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) - return _internal_stream_id(); +inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::mode() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetModeResponse.mode) + return _internal_mode(); } -inline void StopVideoResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) +inline void SetModeResponse::set_mode(::mavsdk::rpc::camera_server::Mode value) { + _internal_set_mode(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetModeResponse.mode) } -inline ::int32_t StopVideoResponse::_internal_stream_id() const { +inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::_internal_mode() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.stream_id_; + return static_cast<::mavsdk::rpc::camera_server::Mode>(_impl_.mode_); } -inline void StopVideoResponse::_internal_set_stream_id(::int32_t value) { +inline void SetModeResponse::_internal_set_mode(::mavsdk::rpc::camera_server::Mode value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.stream_id_ = value; + _impl_.mode_ = value; } // ------------------------------------------------------------------- -// RespondStopVideoRequest +// RespondSetModeRequest -// .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; -inline void RespondStopVideoRequest::clear_stop_video_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback set_mode_feedback = 1; +inline void RespondSetModeRequest::clear_set_mode_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.stop_video_feedback_ = 0; + _impl_.set_mode_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoRequest::stop_video_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoRequest.stop_video_feedback) - return _internal_stop_video_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondSetModeRequest::set_mode_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondSetModeRequest.set_mode_feedback) + return _internal_set_mode_feedback(); } -inline void RespondStopVideoRequest::set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_stop_video_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStopVideoRequest.stop_video_feedback) +inline void RespondSetModeRequest::set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_set_mode_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondSetModeRequest.set_mode_feedback) } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoRequest::_internal_stop_video_feedback() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondSetModeRequest::_internal_set_mode_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.stop_video_feedback_); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.set_mode_feedback_); } -inline void RespondStopVideoRequest::_internal_set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondSetModeRequest::_internal_set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.stop_video_feedback_ = value; + _impl_.set_mode_feedback_ = value; } // ------------------------------------------------------------------- -// RespondStopVideoResponse +// RespondSetModeResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondStopVideoResponse::has_camera_server_result() const { +inline bool RespondSetModeResponse::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 RespondStopVideoResponse::clear_camera_server_result() { +inline void RespondSetModeResponse::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& RespondStopVideoResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondSetModeResponse::_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& RespondStopVideoResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondSetModeResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondStopVideoResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondSetModeResponse::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_); @@ -11319,9 +14509,9 @@ inline void RespondStopVideoResponse::unsafe_arena_set_allocated_camera_server_r } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -11340,16 +14530,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoRespons #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondSetModeResponse.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* RespondStopVideoResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -11358,12 +14548,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoRespons } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::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.RespondStopVideoResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) return _msg; } -inline void RespondStopVideoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondSetModeResponse::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) { @@ -11381,110 +14571,106 @@ inline void RespondStopVideoResponse::set_allocated_camera_server_result(::mavsd } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeStartVideoStreamingRequest +// SubscribeStorageInformationRequest // ------------------------------------------------------------------- -// StartVideoStreamingResponse +// StorageInformationResponse -// int32 stream_id = 1; -inline void StartVideoStreamingResponse::clear_stream_id() { +// int32 storage_id = 1; +inline void StorageInformationResponse::clear_storage_id() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.stream_id_ = 0; + _impl_.storage_id_ = 0; } -inline ::int32_t StartVideoStreamingResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) - return _internal_stream_id(); +inline ::int32_t StorageInformationResponse::storage_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformationResponse.storage_id) + return _internal_storage_id(); } -inline void StartVideoStreamingResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) +inline void StorageInformationResponse::set_storage_id(::int32_t value) { + _internal_set_storage_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformationResponse.storage_id) } -inline ::int32_t StartVideoStreamingResponse::_internal_stream_id() const { +inline ::int32_t StorageInformationResponse::_internal_storage_id() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.stream_id_; + return _impl_.storage_id_; } -inline void StartVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { +inline void StorageInformationResponse::_internal_set_storage_id(::int32_t value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.stream_id_ = value; + _impl_.storage_id_ = value; } // ------------------------------------------------------------------- -// RespondStartVideoStreamingRequest +// RespondStorageInformationRequest -// .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; -inline void RespondStartVideoStreamingRequest::clear_start_video_streaming_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; +inline void RespondStorageInformationRequest::clear_storage_information_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.start_video_streaming_feedback_ = 0; + _impl_.storage_information_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoStreamingRequest::start_video_streaming_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest.start_video_streaming_feedback) - return _internal_start_video_streaming_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStorageInformationRequest::storage_information_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information_feedback) + return _internal_storage_information_feedback(); } -inline void RespondStartVideoStreamingRequest::set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_start_video_streaming_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest.start_video_streaming_feedback) +inline void RespondStorageInformationRequest::set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_storage_information_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information_feedback) } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoStreamingRequest::_internal_start_video_streaming_feedback() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStorageInformationRequest::_internal_storage_information_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.start_video_streaming_feedback_); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.storage_information_feedback_); } -inline void RespondStartVideoStreamingRequest::_internal_set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondStorageInformationRequest::_internal_set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.start_video_streaming_feedback_ = value; + _impl_.storage_information_feedback_ = value; } -// ------------------------------------------------------------------- - -// RespondStartVideoStreamingResponse - -// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondStartVideoStreamingResponse::has_camera_server_result() const { +// .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; +inline bool RespondStorageInformationRequest::has_storage_information() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.storage_information_ != nullptr); return value; } -inline void RespondStartVideoStreamingResponse::clear_camera_server_result() { +inline void RespondStorageInformationRequest::clear_storage_information() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + if (_impl_.storage_information_ != nullptr) _impl_.storage_information_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoStreamingResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::StorageInformation& RespondStorageInformationRequest::_internal_storage_information() 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_); + const ::mavsdk::rpc::camera_server::StorageInformation* p = _impl_.storage_information_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_StorageInformation_default_instance_); } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoStreamingResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) - return _internal_camera_server_result(); +inline const ::mavsdk::rpc::camera_server::StorageInformation& RespondStorageInformationRequest::storage_information() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) + return _internal_storage_information(); } -inline void RespondStartVideoStreamingResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStorageInformationRequest::unsafe_arena_set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.camera_server_result_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.storage_information_); } - _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); + _impl_.storage_information_ = reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(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.RespondStartVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::release_storage_information() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::CameraServerResult* released = _impl_.camera_server_result_; - _impl_.camera_server_result_ = nullptr; + ::mavsdk::rpc::camera_server::StorageInformation* released = _impl_.storage_information_; + _impl_.storage_information_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -11498,38 +14684,38 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStream #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::unsafe_arena_release_storage_information() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; - _impl_.camera_server_result_ = nullptr; + ::mavsdk::rpc::camera_server::StorageInformation* temp = _impl_.storage_information_; + _impl_.storage_information_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::_internal_mutable_storage_information() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.camera_server_result_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArena()); - _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(p); + if (_impl_.storage_information_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::StorageInformation>(GetArena()); + _impl_.storage_information_ = reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(p); } - return _impl_.camera_server_result_; + return _impl_.storage_information_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::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.RespondStartVideoStreamingResponse.camera_server_result) +inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::mutable_storage_information() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::camera_server::StorageInformation* _msg = _internal_mutable_storage_information(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) return _msg; } -inline void RespondStartVideoStreamingResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStorageInformationRequest::set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* 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::CameraServerResult*>(_impl_.camera_server_result_); + delete reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(_impl_.storage_information_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } @@ -11538,93 +14724,35 @@ inline void RespondStartVideoStreamingResponse::set_allocated_camera_server_resu _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) -} - -// ------------------------------------------------------------------- - -// SubscribeStopVideoStreamingRequest - -// ------------------------------------------------------------------- - -// StopVideoStreamingResponse - -// int32 stream_id = 1; -inline void StopVideoStreamingResponse::clear_stream_id() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.stream_id_ = 0; -} -inline ::int32_t StopVideoStreamingResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) - return _internal_stream_id(); -} -inline void StopVideoStreamingResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) -} -inline ::int32_t StopVideoStreamingResponse::_internal_stream_id() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.stream_id_; -} -inline void StopVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.stream_id_ = value; -} - -// ------------------------------------------------------------------- - -// RespondStopVideoStreamingRequest - -// .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; -inline void RespondStopVideoStreamingRequest::clear_stop_video_streaming_feedback() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.stop_video_streaming_feedback_ = 0; -} -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoStreamingRequest::stop_video_streaming_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest.stop_video_streaming_feedback) - return _internal_stop_video_streaming_feedback(); -} -inline void RespondStopVideoStreamingRequest::set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_stop_video_streaming_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest.stop_video_streaming_feedback) -} -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoStreamingRequest::_internal_stop_video_streaming_feedback() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.stop_video_streaming_feedback_); -} -inline void RespondStopVideoStreamingRequest::_internal_set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.stop_video_streaming_feedback_ = value; + _impl_.storage_information_ = reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) } // ------------------------------------------------------------------- -// RespondStopVideoStreamingResponse +// RespondStorageInformationResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondStopVideoStreamingResponse::has_camera_server_result() const { +inline bool RespondStorageInformationResponse::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 RespondStopVideoStreamingResponse::clear_camera_server_result() { +inline void RespondStorageInformationResponse::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& RespondStopVideoStreamingResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStorageInformationResponse::_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& RespondStopVideoStreamingResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStorageInformationResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondStopVideoStreamingResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStorageInformationResponse::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_); @@ -11635,9 +14763,9 @@ inline void RespondStopVideoStreamingResponse::unsafe_arena_set_allocated_camera } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -11656,16 +14784,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreami #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStorageInformationResponse.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* RespondStopVideoStreamingResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -11674,12 +14802,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreami } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::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.RespondStopVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) return _msg; } -inline void RespondStopVideoStreamingResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondStorageInformationResponse::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) { @@ -11697,92 +14825,188 @@ inline void RespondStopVideoStreamingResponse::set_allocated_camera_server_resul } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeSetModeRequest +// SubscribeCaptureStatusRequest // ------------------------------------------------------------------- -// SetModeResponse +// CaptureStatusResponse -// .mavsdk.rpc.camera_server.Mode mode = 1; -inline void SetModeResponse::clear_mode() { +// int32 reserved = 1; +inline void CaptureStatusResponse::clear_reserved() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.mode_ = 0; + _impl_.reserved_ = 0; } -inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::mode() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetModeResponse.mode) - return _internal_mode(); +inline ::int32_t CaptureStatusResponse::reserved() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatusResponse.reserved) + return _internal_reserved(); } -inline void SetModeResponse::set_mode(::mavsdk::rpc::camera_server::Mode value) { - _internal_set_mode(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetModeResponse.mode) +inline void CaptureStatusResponse::set_reserved(::int32_t value) { + _internal_set_reserved(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatusResponse.reserved) } -inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::_internal_mode() const { +inline ::int32_t CaptureStatusResponse::_internal_reserved() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::Mode>(_impl_.mode_); + return _impl_.reserved_; } -inline void SetModeResponse::_internal_set_mode(::mavsdk::rpc::camera_server::Mode value) { +inline void CaptureStatusResponse::_internal_set_reserved(::int32_t value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.mode_ = value; + _impl_.reserved_ = value; } // ------------------------------------------------------------------- -// RespondSetModeRequest +// RespondCaptureStatusRequest -// .mavsdk.rpc.camera_server.CameraFeedback set_mode_feedback = 1; -inline void RespondSetModeRequest::clear_set_mode_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; +inline void RespondCaptureStatusRequest::clear_capture_status_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.set_mode_feedback_ = 0; + _impl_.capture_status_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondSetModeRequest::set_mode_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondSetModeRequest.set_mode_feedback) - return _internal_set_mode_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondCaptureStatusRequest::capture_status_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status_feedback) + return _internal_capture_status_feedback(); +} +inline void RespondCaptureStatusRequest::set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_capture_status_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondCaptureStatusRequest::_internal_capture_status_feedback() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.capture_status_feedback_); +} +inline void RespondCaptureStatusRequest::_internal_set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.capture_status_feedback_ = value; +} + +// .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; +inline bool RespondCaptureStatusRequest::has_capture_status() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.capture_status_ != nullptr); + return value; +} +inline void RespondCaptureStatusRequest::clear_capture_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.capture_status_ != nullptr) _impl_.capture_status_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CaptureStatus& RespondCaptureStatusRequest::_internal_capture_status() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::camera_server::CaptureStatus* p = _impl_.capture_status_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_CaptureStatus_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CaptureStatus& RespondCaptureStatusRequest::capture_status() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) + return _internal_capture_status(); +} +inline void RespondCaptureStatusRequest::unsafe_arena_set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.capture_status_); + } + _impl_.capture_status_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(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.RespondCaptureStatusRequest.capture_status) +} +inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::release_capture_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CaptureStatus* released = _impl_.capture_status_; + _impl_.capture_status_ = 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::CaptureStatus* RespondCaptureStatusRequest::unsafe_arena_release_capture_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CaptureStatus* temp = _impl_.capture_status_; + _impl_.capture_status_ = nullptr; + return temp; } -inline void RespondSetModeRequest::set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_set_mode_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondSetModeRequest.set_mode_feedback) +inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::_internal_mutable_capture_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.capture_status_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureStatus>(GetArena()); + _impl_.capture_status_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(p); + } + return _impl_.capture_status_; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondSetModeRequest::_internal_set_mode_feedback() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.set_mode_feedback_); +inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::mutable_capture_status() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::camera_server::CaptureStatus* _msg = _internal_mutable_capture_status(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) + return _msg; } -inline void RespondSetModeRequest::_internal_set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondCaptureStatusRequest::set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* value) { + ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.set_mode_feedback_ = value; + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(_impl_.capture_status_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(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_.capture_status_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) } // ------------------------------------------------------------------- -// RespondSetModeResponse +// RespondCaptureStatusResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondSetModeResponse::has_camera_server_result() const { +inline bool RespondCaptureStatusResponse::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 RespondSetModeResponse::clear_camera_server_result() { +inline void RespondCaptureStatusResponse::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& RespondSetModeResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondCaptureStatusResponse::_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& RespondSetModeResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondCaptureStatusResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondSetModeResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondCaptureStatusResponse::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_); @@ -11793,9 +15017,9 @@ inline void RespondSetModeResponse::unsafe_arena_set_allocated_camera_server_res } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -11814,16 +15038,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse: #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.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* RespondSetModeResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -11832,12 +15056,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse: } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::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.RespondSetModeResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) return _msg; } -inline void RespondSetModeResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondCaptureStatusResponse::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) { @@ -11855,35 +15079,35 @@ inline void RespondSetModeResponse::set_allocated_camera_server_result(::mavsdk: } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeStorageInformationRequest +// SubscribeFormatStorageRequest // ------------------------------------------------------------------- -// StorageInformationResponse +// FormatStorageResponse // int32 storage_id = 1; -inline void StorageInformationResponse::clear_storage_id() { +inline void FormatStorageResponse::clear_storage_id() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.storage_id_ = 0; } -inline ::int32_t StorageInformationResponse::storage_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformationResponse.storage_id) +inline ::int32_t FormatStorageResponse::storage_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.FormatStorageResponse.storage_id) return _internal_storage_id(); } -inline void StorageInformationResponse::set_storage_id(::int32_t value) { +inline void FormatStorageResponse::set_storage_id(::int32_t value) { _internal_set_storage_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformationResponse.storage_id) + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.FormatStorageResponse.storage_id) } -inline ::int32_t StorageInformationResponse::_internal_storage_id() const { +inline ::int32_t FormatStorageResponse::_internal_storage_id() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); return _impl_.storage_id_; } -inline void StorageInformationResponse::_internal_set_storage_id(::int32_t value) { +inline void FormatStorageResponse::_internal_set_storage_id(::int32_t value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; _impl_.storage_id_ = value; @@ -11891,70 +15115,74 @@ inline void StorageInformationResponse::_internal_set_storage_id(::int32_t value // ------------------------------------------------------------------- -// RespondStorageInformationRequest +// RespondFormatStorageRequest -// .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; -inline void RespondStorageInformationRequest::clear_storage_information_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; +inline void RespondFormatStorageRequest::clear_format_storage_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.storage_information_feedback_ = 0; + _impl_.format_storage_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStorageInformationRequest::storage_information_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information_feedback) - return _internal_storage_information_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondFormatStorageRequest::format_storage_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondFormatStorageRequest.format_storage_feedback) + return _internal_format_storage_feedback(); } -inline void RespondStorageInformationRequest::set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_storage_information_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information_feedback) +inline void RespondFormatStorageRequest::set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_format_storage_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondFormatStorageRequest.format_storage_feedback) } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStorageInformationRequest::_internal_storage_information_feedback() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondFormatStorageRequest::_internal_format_storage_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.storage_information_feedback_); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.format_storage_feedback_); } -inline void RespondStorageInformationRequest::_internal_set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondFormatStorageRequest::_internal_set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.storage_information_feedback_ = value; + _impl_.format_storage_feedback_ = value; } -// .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; -inline bool RespondStorageInformationRequest::has_storage_information() const { +// ------------------------------------------------------------------- + +// RespondFormatStorageResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondFormatStorageResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.storage_information_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void RespondStorageInformationRequest::clear_storage_information() { +inline void RespondFormatStorageResponse::clear_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.storage_information_ != nullptr) _impl_.storage_information_->Clear(); + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::StorageInformation& RespondStorageInformationRequest::_internal_storage_information() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondFormatStorageResponse::_internal_camera_server_result() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::camera_server::StorageInformation* p = _impl_.storage_information_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_StorageInformation_default_instance_); + 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::StorageInformation& RespondStorageInformationRequest::storage_information() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) - return _internal_storage_information(); +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondFormatStorageResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) + return _internal_camera_server_result(); } -inline void RespondStorageInformationRequest::unsafe_arena_set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* value) { +inline void RespondFormatStorageResponse::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_.storage_information_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.camera_server_result_); } - _impl_.storage_information_ = reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(value); + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(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.RespondStorageInformationRequest.storage_information) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::release_storage_information() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::StorageInformation* released = _impl_.storage_information_; - _impl_.storage_information_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* released = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -11968,38 +15196,38 @@ inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformati #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::unsafe_arena_release_storage_information() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::StorageInformation* temp = _impl_.storage_information_; - _impl_.storage_information_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::_internal_mutable_storage_information() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.storage_information_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::StorageInformation>(GetArena()); - _impl_.storage_information_ = reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(p); + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArena()); + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(p); } - return _impl_.storage_information_; + return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::mutable_storage_information() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::camera_server::StorageInformation* _msg = _internal_mutable_storage_information(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::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.RespondFormatStorageResponse.camera_server_result) return _msg; } -inline void RespondStorageInformationRequest::set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* value) { +inline void RespondFormatStorageResponse::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) { - delete reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(_impl_.storage_information_); + delete reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(_impl_.camera_server_result_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } @@ -12008,35 +15236,93 @@ inline void RespondStorageInformationRequest::set_allocated_storage_information( _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.storage_information_ = reinterpret_cast<::mavsdk::rpc::camera_server::StorageInformation*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) } // ------------------------------------------------------------------- -// RespondStorageInformationResponse +// SubscribeResetSettingsRequest + +// ------------------------------------------------------------------- + +// ResetSettingsResponse + +// int32 reserved = 1; +inline void ResetSettingsResponse::clear_reserved() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.reserved_ = 0; +} +inline ::int32_t ResetSettingsResponse::reserved() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) + return _internal_reserved(); +} +inline void ResetSettingsResponse::set_reserved(::int32_t value) { + _internal_set_reserved(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) +} +inline ::int32_t ResetSettingsResponse::_internal_reserved() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.reserved_; +} +inline void ResetSettingsResponse::_internal_set_reserved(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.reserved_ = value; +} + +// ------------------------------------------------------------------- + +// RespondResetSettingsRequest + +// .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; +inline void RespondResetSettingsRequest::clear_reset_settings_feedback() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.reset_settings_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondResetSettingsRequest::reset_settings_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondResetSettingsRequest.reset_settings_feedback) + return _internal_reset_settings_feedback(); +} +inline void RespondResetSettingsRequest::set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_reset_settings_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondResetSettingsRequest.reset_settings_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondResetSettingsRequest::_internal_reset_settings_feedback() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.reset_settings_feedback_); +} +inline void RespondResetSettingsRequest::_internal_set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.reset_settings_feedback_ = value; +} + +// ------------------------------------------------------------------- + +// RespondResetSettingsResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondStorageInformationResponse::has_camera_server_result() const { +inline bool RespondResetSettingsResponse::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 RespondStorageInformationResponse::clear_camera_server_result() { +inline void RespondResetSettingsResponse::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& RespondStorageInformationResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondResetSettingsResponse::_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& RespondStorageInformationResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondResetSettingsResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondStorageInformationResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondResetSettingsResponse::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_); @@ -12047,9 +15333,9 @@ inline void RespondStorageInformationResponse::unsafe_arena_set_allocated_camera } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -12068,16 +15354,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformati #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondResetSettingsResponse.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* RespondStorageInformationResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -12086,12 +15372,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformati } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::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.RespondStorageInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) return _msg; } -inline void RespondStorageInformationResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondResetSettingsResponse::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) { @@ -12109,35 +15395,35 @@ inline void RespondStorageInformationResponse::set_allocated_camera_server_resul } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeCaptureStatusRequest +// SubscribeZoomInStartRequest // ------------------------------------------------------------------- -// CaptureStatusResponse +// ZoomInStartResponse // int32 reserved = 1; -inline void CaptureStatusResponse::clear_reserved() { +inline void ZoomInStartResponse::clear_reserved() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.reserved_ = 0; } -inline ::int32_t CaptureStatusResponse::reserved() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatusResponse.reserved) +inline ::int32_t ZoomInStartResponse::reserved() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ZoomInStartResponse.reserved) return _internal_reserved(); } -inline void CaptureStatusResponse::set_reserved(::int32_t value) { +inline void ZoomInStartResponse::set_reserved(::int32_t value) { _internal_set_reserved(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatusResponse.reserved) + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ZoomInStartResponse.reserved) } -inline ::int32_t CaptureStatusResponse::_internal_reserved() const { +inline ::int32_t ZoomInStartResponse::_internal_reserved() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); return _impl_.reserved_; } -inline void CaptureStatusResponse::_internal_set_reserved(::int32_t value) { +inline void ZoomInStartResponse::_internal_set_reserved(::int32_t value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; _impl_.reserved_ = value; @@ -12145,70 +15431,74 @@ inline void CaptureStatusResponse::_internal_set_reserved(::int32_t value) { // ------------------------------------------------------------------- -// RespondCaptureStatusRequest +// RespondZoomInStartRequest -// .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; -inline void RespondCaptureStatusRequest::clear_capture_status_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback zoom_in_start_feedback = 1; +inline void RespondZoomInStartRequest::clear_zoom_in_start_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.capture_status_feedback_ = 0; + _impl_.zoom_in_start_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondCaptureStatusRequest::capture_status_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status_feedback) - return _internal_capture_status_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondZoomInStartRequest::zoom_in_start_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondZoomInStartRequest.zoom_in_start_feedback) + return _internal_zoom_in_start_feedback(); } -inline void RespondCaptureStatusRequest::set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_capture_status_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status_feedback) +inline void RespondZoomInStartRequest::set_zoom_in_start_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_zoom_in_start_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondZoomInStartRequest.zoom_in_start_feedback) } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondCaptureStatusRequest::_internal_capture_status_feedback() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondZoomInStartRequest::_internal_zoom_in_start_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.capture_status_feedback_); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.zoom_in_start_feedback_); } -inline void RespondCaptureStatusRequest::_internal_set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondZoomInStartRequest::_internal_set_zoom_in_start_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.capture_status_feedback_ = value; + _impl_.zoom_in_start_feedback_ = value; } -// .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; -inline bool RespondCaptureStatusRequest::has_capture_status() const { +// ------------------------------------------------------------------- + +// RespondZoomInStartResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondZoomInStartResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.capture_status_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void RespondCaptureStatusRequest::clear_capture_status() { +inline void RespondZoomInStartResponse::clear_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.capture_status_ != nullptr) _impl_.capture_status_->Clear(); + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::CaptureStatus& RespondCaptureStatusRequest::_internal_capture_status() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomInStartResponse::_internal_camera_server_result() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::camera_server::CaptureStatus* p = _impl_.capture_status_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera_server::_CaptureStatus_default_instance_); + 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::CaptureStatus& RespondCaptureStatusRequest::capture_status() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) - return _internal_capture_status(); +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomInStartResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondZoomInStartResponse.camera_server_result) + return _internal_camera_server_result(); } -inline void RespondCaptureStatusRequest::unsafe_arena_set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* value) { +inline void RespondZoomInStartResponse::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_.capture_status_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.camera_server_result_); } - _impl_.capture_status_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(value); + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(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.RespondCaptureStatusRequest.capture_status) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondZoomInStartResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::release_capture_status() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomInStartResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::CaptureStatus* released = _impl_.capture_status_; - _impl_.capture_status_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* released = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -12222,38 +15512,38 @@ inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest: #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::unsafe_arena_release_capture_status() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomInStartResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondZoomInStartResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::CaptureStatus* temp = _impl_.capture_status_; - _impl_.capture_status_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::_internal_mutable_capture_status() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomInStartResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.capture_status_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureStatus>(GetArena()); - _impl_.capture_status_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(p); + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArena()); + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(p); } - return _impl_.capture_status_; + return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::mutable_capture_status() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::camera_server::CaptureStatus* _msg = _internal_mutable_capture_status(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomInStartResponse::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.RespondZoomInStartResponse.camera_server_result) return _msg; } -inline void RespondCaptureStatusRequest::set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* value) { +inline void RespondZoomInStartResponse::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) { - delete reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(_impl_.capture_status_); + delete reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(_impl_.camera_server_result_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } @@ -12262,35 +15552,93 @@ inline void RespondCaptureStatusRequest::set_allocated_capture_status(::mavsdk:: _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.capture_status_ = reinterpret_cast<::mavsdk::rpc::camera_server::CaptureStatus*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) + _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondZoomInStartResponse.camera_server_result) } // ------------------------------------------------------------------- -// RespondCaptureStatusResponse +// SubscribeZoomOutStartRequest + +// ------------------------------------------------------------------- + +// ZoomOutStartResponse + +// int32 reserved = 1; +inline void ZoomOutStartResponse::clear_reserved() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.reserved_ = 0; +} +inline ::int32_t ZoomOutStartResponse::reserved() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ZoomOutStartResponse.reserved) + return _internal_reserved(); +} +inline void ZoomOutStartResponse::set_reserved(::int32_t value) { + _internal_set_reserved(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ZoomOutStartResponse.reserved) +} +inline ::int32_t ZoomOutStartResponse::_internal_reserved() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.reserved_; +} +inline void ZoomOutStartResponse::_internal_set_reserved(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.reserved_ = value; +} + +// ------------------------------------------------------------------- + +// RespondZoomOutStartRequest + +// .mavsdk.rpc.camera_server.CameraFeedback zoom_out_start_feedback = 1; +inline void RespondZoomOutStartRequest::clear_zoom_out_start_feedback() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.zoom_out_start_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondZoomOutStartRequest::zoom_out_start_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondZoomOutStartRequest.zoom_out_start_feedback) + return _internal_zoom_out_start_feedback(); +} +inline void RespondZoomOutStartRequest::set_zoom_out_start_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_zoom_out_start_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondZoomOutStartRequest.zoom_out_start_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondZoomOutStartRequest::_internal_zoom_out_start_feedback() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.zoom_out_start_feedback_); +} +inline void RespondZoomOutStartRequest::_internal_set_zoom_out_start_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.zoom_out_start_feedback_ = value; +} + +// ------------------------------------------------------------------- + +// RespondZoomOutStartResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondCaptureStatusResponse::has_camera_server_result() const { +inline bool RespondZoomOutStartResponse::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 RespondCaptureStatusResponse::clear_camera_server_result() { +inline void RespondZoomOutStartResponse::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& RespondCaptureStatusResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomOutStartResponse::_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& RespondCaptureStatusResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomOutStartResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondZoomOutStartResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondCaptureStatusResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondZoomOutStartResponse::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_); @@ -12301,9 +15649,9 @@ inline void RespondCaptureStatusResponse::unsafe_arena_set_allocated_camera_serv } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondZoomOutStartResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomOutStartResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -12322,16 +15670,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusRes #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomOutStartResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondZoomOutStartResponse.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* RespondCaptureStatusResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomOutStartResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -12340,12 +15688,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusRes } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomOutStartResponse::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.RespondCaptureStatusResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondZoomOutStartResponse.camera_server_result) return _msg; } -inline void RespondCaptureStatusResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondZoomOutStartResponse::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) { @@ -12363,92 +15711,92 @@ inline void RespondCaptureStatusResponse::set_allocated_camera_server_result(::m } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondZoomOutStartResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeFormatStorageRequest +// SubscribeZoomStopRequest // ------------------------------------------------------------------- -// FormatStorageResponse +// ZoomStopResponse -// int32 storage_id = 1; -inline void FormatStorageResponse::clear_storage_id() { +// int32 reserved = 1; +inline void ZoomStopResponse::clear_reserved() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.storage_id_ = 0; + _impl_.reserved_ = 0; } -inline ::int32_t FormatStorageResponse::storage_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.FormatStorageResponse.storage_id) - return _internal_storage_id(); +inline ::int32_t ZoomStopResponse::reserved() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ZoomStopResponse.reserved) + return _internal_reserved(); } -inline void FormatStorageResponse::set_storage_id(::int32_t value) { - _internal_set_storage_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.FormatStorageResponse.storage_id) +inline void ZoomStopResponse::set_reserved(::int32_t value) { + _internal_set_reserved(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ZoomStopResponse.reserved) } -inline ::int32_t FormatStorageResponse::_internal_storage_id() const { +inline ::int32_t ZoomStopResponse::_internal_reserved() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.storage_id_; + return _impl_.reserved_; } -inline void FormatStorageResponse::_internal_set_storage_id(::int32_t value) { +inline void ZoomStopResponse::_internal_set_reserved(::int32_t value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.storage_id_ = value; + _impl_.reserved_ = value; } // ------------------------------------------------------------------- -// RespondFormatStorageRequest +// RespondZoomStopRequest -// .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; -inline void RespondFormatStorageRequest::clear_format_storage_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback zoom_stop_feedback = 1; +inline void RespondZoomStopRequest::clear_zoom_stop_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.format_storage_feedback_ = 0; + _impl_.zoom_stop_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondFormatStorageRequest::format_storage_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondFormatStorageRequest.format_storage_feedback) - return _internal_format_storage_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondZoomStopRequest::zoom_stop_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondZoomStopRequest.zoom_stop_feedback) + return _internal_zoom_stop_feedback(); } -inline void RespondFormatStorageRequest::set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_format_storage_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondFormatStorageRequest.format_storage_feedback) +inline void RespondZoomStopRequest::set_zoom_stop_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_zoom_stop_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondZoomStopRequest.zoom_stop_feedback) } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondFormatStorageRequest::_internal_format_storage_feedback() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondZoomStopRequest::_internal_zoom_stop_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.format_storage_feedback_); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.zoom_stop_feedback_); } -inline void RespondFormatStorageRequest::_internal_set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondZoomStopRequest::_internal_set_zoom_stop_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.format_storage_feedback_ = value; + _impl_.zoom_stop_feedback_ = value; } // ------------------------------------------------------------------- -// RespondFormatStorageResponse +// RespondZoomStopResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondFormatStorageResponse::has_camera_server_result() const { +inline bool RespondZoomStopResponse::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 RespondFormatStorageResponse::clear_camera_server_result() { +inline void RespondZoomStopResponse::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& RespondFormatStorageResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomStopResponse::_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& RespondFormatStorageResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomStopResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondZoomStopResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondFormatStorageResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondZoomStopResponse::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_); @@ -12459,9 +15807,9 @@ inline void RespondFormatStorageResponse::unsafe_arena_set_allocated_camera_serv } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondZoomStopResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomStopResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -12480,16 +15828,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageRes #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomStopResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondZoomStopResponse.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* RespondFormatStorageResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomStopResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -12498,12 +15846,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageRes } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomStopResponse::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.RespondFormatStorageResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondZoomStopResponse.camera_server_result) return _msg; } -inline void RespondFormatStorageResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondZoomStopResponse::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) { @@ -12521,92 +15869,92 @@ inline void RespondFormatStorageResponse::set_allocated_camera_server_result(::m } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondZoomStopResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeResetSettingsRequest +// SubscribeZoomRangeRequest // ------------------------------------------------------------------- -// ResetSettingsResponse +// ZoomRangeResponse -// int32 reserved = 1; -inline void ResetSettingsResponse::clear_reserved() { +// float factor = 1; +inline void ZoomRangeResponse::clear_factor() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.reserved_ = 0; + _impl_.factor_ = 0; } -inline ::int32_t ResetSettingsResponse::reserved() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) - return _internal_reserved(); +inline float ZoomRangeResponse::factor() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ZoomRangeResponse.factor) + return _internal_factor(); } -inline void ResetSettingsResponse::set_reserved(::int32_t value) { - _internal_set_reserved(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) +inline void ZoomRangeResponse::set_factor(float value) { + _internal_set_factor(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ZoomRangeResponse.factor) } -inline ::int32_t ResetSettingsResponse::_internal_reserved() const { +inline float ZoomRangeResponse::_internal_factor() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.reserved_; + return _impl_.factor_; } -inline void ResetSettingsResponse::_internal_set_reserved(::int32_t value) { +inline void ZoomRangeResponse::_internal_set_factor(float value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.reserved_ = value; + _impl_.factor_ = value; } // ------------------------------------------------------------------- -// RespondResetSettingsRequest +// RespondZoomRangeRequest -// .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; -inline void RespondResetSettingsRequest::clear_reset_settings_feedback() { +// .mavsdk.rpc.camera_server.CameraFeedback zoom_range_feedback = 1; +inline void RespondZoomRangeRequest::clear_zoom_range_feedback() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.reset_settings_feedback_ = 0; + _impl_.zoom_range_feedback_ = 0; } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondResetSettingsRequest::reset_settings_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondResetSettingsRequest.reset_settings_feedback) - return _internal_reset_settings_feedback(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondZoomRangeRequest::zoom_range_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondZoomRangeRequest.zoom_range_feedback) + return _internal_zoom_range_feedback(); } -inline void RespondResetSettingsRequest::set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { - _internal_set_reset_settings_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondResetSettingsRequest.reset_settings_feedback) +inline void RespondZoomRangeRequest::set_zoom_range_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_zoom_range_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondZoomRangeRequest.zoom_range_feedback) } -inline ::mavsdk::rpc::camera_server::CameraFeedback RespondResetSettingsRequest::_internal_reset_settings_feedback() const { +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondZoomRangeRequest::_internal_zoom_range_feedback() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.reset_settings_feedback_); + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.zoom_range_feedback_); } -inline void RespondResetSettingsRequest::_internal_set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { +inline void RespondZoomRangeRequest::_internal_set_zoom_range_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ; - _impl_.reset_settings_feedback_ = value; + _impl_.zoom_range_feedback_ = value; } // ------------------------------------------------------------------- -// RespondResetSettingsResponse +// RespondZoomRangeResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondResetSettingsResponse::has_camera_server_result() const { +inline bool RespondZoomRangeResponse::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 RespondResetSettingsResponse::clear_camera_server_result() { +inline void RespondZoomRangeResponse::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& RespondResetSettingsResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomRangeResponse::_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& RespondResetSettingsResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondZoomRangeResponse::camera_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondZoomRangeResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondResetSettingsResponse::unsafe_arena_set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondZoomRangeResponse::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_); @@ -12617,9 +15965,9 @@ inline void RespondResetSettingsResponse::unsafe_arena_set_allocated_camera_serv } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondZoomRangeResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomRangeResponse::release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; @@ -12638,16 +15986,16 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsRes #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::unsafe_arena_release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomRangeResponse::unsafe_arena_release_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondZoomRangeResponse.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* RespondResetSettingsResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomRangeResponse::_internal_mutable_camera_server_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { @@ -12656,12 +16004,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsRes } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::mutable_camera_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondZoomRangeResponse::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.RespondResetSettingsResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondZoomRangeResponse.camera_server_result) return _msg; } -inline void RespondResetSettingsResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* value) { +inline void RespondZoomRangeResponse::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) { @@ -12679,7 +16027,7 @@ inline void RespondResetSettingsResponse::set_allocated_camera_server_result(::m } _impl_.camera_server_result_ = reinterpret_cast<::mavsdk::rpc::camera_server::CameraServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondZoomRangeResponse.camera_server_result) } // ------------------------------------------------------------------- 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..347e185af9 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 @@ -1414,6 +1414,294 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status SubscribeZoomInStart( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeZoomInStartRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::ZoomInStartHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_zoom_in_start( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t zoom_in_start) { + rpc::camera_server::ZoomInStartResponse rpc_response; + + rpc_response.set_reserved(zoom_in_start); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_zoom_in_start(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status RespondZoomInStart( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondZoomInStartRequest* request, + rpc::camera_server::RespondZoomInStartResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondZoomInStart sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_zoom_in_start( + translateFromRpcCameraFeedback(request->zoom_in_start_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status SubscribeZoomOutStart( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeZoomOutStartRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::ZoomOutStartHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_zoom_out_start( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t zoom_out_start) { + rpc::camera_server::ZoomOutStartResponse rpc_response; + + rpc_response.set_reserved(zoom_out_start); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_zoom_out_start(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status RespondZoomOutStart( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondZoomOutStartRequest* request, + rpc::camera_server::RespondZoomOutStartResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondZoomOutStart sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_zoom_out_start( + translateFromRpcCameraFeedback(request->zoom_out_start_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status SubscribeZoomStop( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeZoomStopRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::ZoomStopHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_zoom_stop( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t zoom_stop) { + rpc::camera_server::ZoomStopResponse rpc_response; + + rpc_response.set_reserved(zoom_stop); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_zoom_stop(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status RespondZoomStop( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondZoomStopRequest* request, + rpc::camera_server::RespondZoomStopResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondZoomStop sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_zoom_stop( + translateFromRpcCameraFeedback(request->zoom_stop_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status SubscribeZoomRange( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeZoomRangeRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::ZoomRangeHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_zoom_range( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const float zoom_range) { + rpc::camera_server::ZoomRangeResponse rpc_response; + + rpc_response.set_factor(zoom_range); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_zoom_range(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status RespondZoomRange( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondZoomRangeRequest* request, + rpc::camera_server::RespondZoomRangeResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondZoomRange sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_zoom_range( + translateFromRpcCameraFeedback(request->zoom_range_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + void stop() { _stopped.store(true);