From b322c21e5c55bf46ed431e374785ee24c8343ccc Mon Sep 17 00:00:00 2001 From: David Lechner Date: Fri, 14 Jan 2022 14:44:29 -0600 Subject: [PATCH 1/6] WIP: add camera server --- examples/CMakeLists.txt | 1 + examples/camera_server/CMakeLists.txt | 22 + examples/camera_server/camera_server.cpp | 121 + proto | 2 +- src/mavsdk/plugins/CMakeLists.txt | 1 + .../plugins/camera_server/CMakeLists.txt | 15 + .../plugins/camera_server/camera_server.cpp | 195 + .../camera_server/camera_server_impl.cpp | 584 +++ .../camera_server/camera_server_impl.h | 85 + .../plugins/camera_server/camera_server.h | 294 ++ src/mavsdk_server/src/CMakeLists.txt | 1 + .../camera_server/camera_server.grpc.pb.cc | 209 + .../camera_server/camera_server.grpc.pb.h | 727 ++++ .../camera_server/camera_server.pb.cc | 3537 ++++++++++++++++ .../camera_server/camera_server.pb.h | 3683 +++++++++++++++++ src/mavsdk_server/src/grpc_server.cpp | 2 + src/mavsdk_server/src/grpc_server.h | 6 + .../camera_server_service_impl.h | 427 ++ 18 files changed, 9911 insertions(+), 1 deletion(-) create mode 100644 examples/camera_server/CMakeLists.txt create mode 100644 examples/camera_server/camera_server.cpp create mode 100644 src/mavsdk/plugins/camera_server/CMakeLists.txt create mode 100644 src/mavsdk/plugins/camera_server/camera_server.cpp create mode 100644 src/mavsdk/plugins/camera_server/camera_server_impl.cpp create mode 100644 src/mavsdk/plugins/camera_server/camera_server_impl.h create mode 100644 src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h create mode 100644 src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc create mode 100644 src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h create mode 100644 src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc create mode 100644 src/mavsdk_server/src/generated/camera_server/camera_server.pb.h create mode 100644 src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 9b12c2b171..b438a17e60 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -11,6 +11,7 @@ add_subdirectory(autopilot_server) add_subdirectory(battery) add_subdirectory(calibrate) add_subdirectory(camera) +add_subdirectory(camera_server) add_subdirectory(camera_settings) add_subdirectory(fly_mission) add_subdirectory(fly_multiple_drones) diff --git a/examples/camera_server/CMakeLists.txt b/examples/camera_server/CMakeLists.txt new file mode 100644 index 0000000000..25ed4e8a50 --- /dev/null +++ b/examples/camera_server/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_server) + +add_executable(camera_server + camera_server.cpp +) + +find_package(MAVSDK REQUIRED) + +target_link_libraries(camera_server + MAVSDK::mavsdk +) + +if(NOT MSVC) + add_compile_options(camera_server PRIVATE -Wall -Wextra) +else() + add_compile_options(camera_server PRIVATE -WX -W2) +endif() diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp new file mode 100644 index 0000000000..d64fe523d6 --- /dev/null +++ b/examples/camera_server/camera_server.cpp @@ -0,0 +1,121 @@ +#include + +#include +#include +#include +#include +#include +#include + +/* + This example runs a MAVLink "camera" utilizing the MAVSDK server plugins + on a separate thread. This uses two MAVSDK instances, one GCS, one camera. + + The main thread acts as a GCS and reads telemetry, parameters, transmits across + a mission, clears the mission, arms the vehicle and then triggers a vehicle takeoff. + + The camera thread handles all the servers and triggers callbacks, publishes telemetry, + handles and stores parameters, prints received missions and sets the vehicle height to 10m on + successful takeoff request. +*/ + +using namespace mavsdk; + +using std::chrono::duration_cast; +using std::chrono::seconds; +using std::chrono::milliseconds; +using std::chrono::system_clock; +using std::this_thread::sleep_for; + +// map of system id to camera server instance +static std::map> all_camera_servers{}; + +void handle_per_system_camera(std::shared_ptr system) +{ + if (all_camera_servers.find(system->get_system_id()) != all_camera_servers.end()) { + std::cerr << "Unexpected duplicate system ID " << +system->get_system_id() << ", ignoring." + << std::endl; + return; + } + + // Create server plugin + auto camera_server = std::make_shared(system); + + all_camera_servers.insert({system->get_system_id(), camera_server}); + + camera_server->set_information({ + .vendor_name = "MAVSDK", + .model_name = "Example Camera Server", + .focal_length_mm = 3.0, + .horizontal_sensor_size_mm = 3.68, + .vertical_sensor_size_mm = 2.76, + .horizontal_resolution_px = 3280, + .vertical_resolution_px = 2464, + }); + + camera_server->set_in_progress(false); + + camera_server->subscribe_take_photo( + [&camera_server](CameraServer::Result result, int32_t index) { + camera_server->set_in_progress(true); + + std::cout << "taking a picture..." << std::endl; + + // TODO : actually capture image here + // simulating with delay + sleep_for(seconds(1)); + + // TODO: populate with telemetry data + auto position = CameraServer::Position{}; + auto attitude = CameraServer::Quaternion{}; + + auto timestamp = + duration_cast(system_clock::now().time_since_epoch()).count(); + auto success = true; + + camera_server->set_in_progress(false); + + camera_server->publish_photo({ + .position = position, + .attitude_quaternion = attitude, + .time_utc_us = static_cast(timestamp), + .is_success = success, + .index = index, + .file_url = {}, + }); + }); + + std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") << " system ID " << +system->get_system_id() << std::endl; +} + +int main(int argc, char** argv) +{ + mavsdk::Mavsdk mavsdk; + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::Configuration::UsageType::Camera); + mavsdk.set_configuration(configuration); + + // 14030 is the default camera port for PX4 SITL + auto result = mavsdk.add_any_connection("udp://:14030"); + if (result == mavsdk::ConnectionResult::Success) { + std::cout << "Created camera server connection" << std::endl; + } + + mavsdk.subscribe_on_new_system([&mavsdk]() { + // REVISIT: is it safe to assume that this will not miss any systems, + // e.g. two discovered at the same time? + auto system = mavsdk.systems().back(); + + handle_per_system_camera(system); + }); + + for (auto&& system : mavsdk.systems()) { + handle_per_system_camera(system); + } + + while (true) { + // TODO: better way to wait forever? + sleep_for(seconds(1)); + } + + return 0; +} \ No newline at end of file diff --git a/proto b/proto index 5cb33bbe09..15bf7f73d2 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 5cb33bbe09bae83105a2eff915a09e3438e9033f +Subproject commit 15bf7f73d2f39ecdd324daace06c2f13860e1508 diff --git a/src/mavsdk/plugins/CMakeLists.txt b/src/mavsdk/plugins/CMakeLists.txt index 7141a16474..fbea854012 100644 --- a/src/mavsdk/plugins/CMakeLists.txt +++ b/src/mavsdk/plugins/CMakeLists.txt @@ -2,6 +2,7 @@ add_subdirectory(action) add_subdirectory(action_server) add_subdirectory(calibration) add_subdirectory(camera) +add_subdirectory(camera_server) add_subdirectory(failure) add_subdirectory(follow_me) add_subdirectory(ftp) diff --git a/src/mavsdk/plugins/camera_server/CMakeLists.txt b/src/mavsdk/plugins/camera_server/CMakeLists.txt new file mode 100644 index 0000000000..b51696f024 --- /dev/null +++ b/src/mavsdk/plugins/camera_server/CMakeLists.txt @@ -0,0 +1,15 @@ +target_sources(mavsdk + PRIVATE + camera_server.cpp + camera_server_impl.cpp +) + +target_include_directories(mavsdk PUBLIC + $ + $ + ) + +install(FILES + include/plugins/camera_server/camera_server.h + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/mavsdk/plugins/camera_server +) \ No newline at end of file diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp new file mode 100644 index 0000000000..136c7dea2d --- /dev/null +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -0,0 +1,195 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/camera_server/camera_server.proto) + +#include + +#include "camera_server_impl.h" +#include "plugins/camera_server/camera_server.h" + +namespace mavsdk { + +using Information = CameraServer::Information; +using Position = CameraServer::Position; +using Quaternion = CameraServer::Quaternion; +using CaptureInfo = CameraServer::CaptureInfo; + + + +CameraServer::CameraServer(System& system) : PluginBase(), _impl{std::make_unique(system)} {} + +CameraServer::CameraServer(std::shared_ptr system) : PluginBase(), _impl{std::make_unique(system)} {} + +CameraServer::~CameraServer() {} + + + + + +CameraServer::Result CameraServer::set_information(Information information) const +{ + return _impl->set_information(information); +} + + + + + +CameraServer::Result CameraServer::set_in_progress(bool in_progress) const +{ + return _impl->set_in_progress(in_progress); +} + + + +void CameraServer::subscribe_take_photo(TakePhotoCallback callback) +{ + _impl->subscribe_take_photo(callback); +} + + + + + + + +CameraServer::Result CameraServer::publish_photo(CaptureInfo capture_info) const +{ + return _impl->publish_photo(capture_info); +} + + + +bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) +{ + return + (rhs.vendor_name == lhs.vendor_name) && + (rhs.model_name == lhs.model_name) && + ((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) || rhs.focal_length_mm == lhs.focal_length_mm) && + ((std::isnan(rhs.horizontal_sensor_size_mm) && std::isnan(lhs.horizontal_sensor_size_mm)) || rhs.horizontal_sensor_size_mm == lhs.horizontal_sensor_size_mm) && + ((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) || rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) && + (rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) && + (rhs.vertical_resolution_px == lhs.vertical_resolution_px); +} + +std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information) +{ + str << std::setprecision(15); + str << "information:" << '\n' + << "{\n"; + str << " vendor_name: " << information.vendor_name << '\n'; + str << " model_name: " << information.model_name << '\n'; + str << " focal_length_mm: " << information.focal_length_mm << '\n'; + str << " horizontal_sensor_size_mm: " << information.horizontal_sensor_size_mm << '\n'; + str << " vertical_sensor_size_mm: " << information.vertical_sensor_size_mm << '\n'; + str << " horizontal_resolution_px: " << information.horizontal_resolution_px << '\n'; + str << " vertical_resolution_px: " << information.vertical_resolution_px << '\n'; + str << '}'; + return str; +} + + +bool operator==(const CameraServer::Position& lhs, const CameraServer::Position& rhs) +{ + return + ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) || rhs.latitude_deg == lhs.latitude_deg) && + ((std::isnan(rhs.longitude_deg) && std::isnan(lhs.longitude_deg)) || rhs.longitude_deg == lhs.longitude_deg) && + ((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) || rhs.absolute_altitude_m == lhs.absolute_altitude_m) && + ((std::isnan(rhs.relative_altitude_m) && std::isnan(lhs.relative_altitude_m)) || rhs.relative_altitude_m == lhs.relative_altitude_m); +} + +std::ostream& operator<<(std::ostream& str, CameraServer::Position const& position) +{ + str << std::setprecision(15); + str << "position:" << '\n' + << "{\n"; + str << " latitude_deg: " << position.latitude_deg << '\n'; + str << " longitude_deg: " << position.longitude_deg << '\n'; + str << " absolute_altitude_m: " << position.absolute_altitude_m << '\n'; + str << " relative_altitude_m: " << position.relative_altitude_m << '\n'; + str << '}'; + return str; +} + + +bool operator==(const CameraServer::Quaternion& lhs, const CameraServer::Quaternion& rhs) +{ + return + ((std::isnan(rhs.w) && std::isnan(lhs.w)) || rhs.w == lhs.w) && + ((std::isnan(rhs.x) && std::isnan(lhs.x)) || rhs.x == lhs.x) && + ((std::isnan(rhs.y) && std::isnan(lhs.y)) || rhs.y == lhs.y) && + ((std::isnan(rhs.z) && std::isnan(lhs.z)) || rhs.z == lhs.z); +} + +std::ostream& operator<<(std::ostream& str, CameraServer::Quaternion const& quaternion) +{ + str << std::setprecision(15); + str << "quaternion:" << '\n' + << "{\n"; + str << " w: " << quaternion.w << '\n'; + str << " x: " << quaternion.x << '\n'; + str << " y: " << quaternion.y << '\n'; + str << " z: " << quaternion.z << '\n'; + str << '}'; + return str; +} + + +bool operator==(const CameraServer::CaptureInfo& lhs, const CameraServer::CaptureInfo& rhs) +{ + return + (rhs.position == lhs.position) && + (rhs.attitude_quaternion == lhs.attitude_quaternion) && + (rhs.time_utc_us == lhs.time_utc_us) && + (rhs.is_success == lhs.is_success) && + (rhs.index == lhs.index) && + (rhs.file_url == lhs.file_url); +} + +std::ostream& operator<<(std::ostream& str, CameraServer::CaptureInfo const& capture_info) +{ + str << std::setprecision(15); + str << "capture_info:" << '\n' + << "{\n"; + str << " position: " << capture_info.position << '\n'; + str << " attitude_quaternion: " << capture_info.attitude_quaternion << '\n'; + str << " time_utc_us: " << capture_info.time_utc_us << '\n'; + str << " is_success: " << capture_info.is_success << '\n'; + str << " index: " << capture_info.index << '\n'; + str << " file_url: " << capture_info.file_url << '\n'; + str << '}'; + return str; +} + + + +std::ostream& operator<<(std::ostream& str, CameraServer::Result const& result) +{ + switch (result) { + case CameraServer::Result::Unknown: + return str << "Unknown"; + case CameraServer::Result::Success: + return str << "Success"; + case CameraServer::Result::InProgress: + return str << "In Progress"; + case CameraServer::Result::Busy: + return str << "Busy"; + case CameraServer::Result::Denied: + return str << "Denied"; + case CameraServer::Result::Error: + return str << "Error"; + case CameraServer::Result::Timeout: + return str << "Timeout"; + case CameraServer::Result::WrongArgument: + return str << "Wrong Argument"; + case CameraServer::Result::NoSystem: + return str << "No System"; + default: + return str << "Unknown"; + } +} + + + + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp new file mode 100644 index 0000000000..edc85367ec --- /dev/null +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -0,0 +1,584 @@ +#include "camera_server_impl.h" +#include "unused.h" + +namespace mavsdk { + +CameraServerImpl::CameraServerImpl(System& system) : PluginImplBase(system) +{ + _parent->register_plugin(this); +} + +CameraServerImpl::CameraServerImpl(std::shared_ptr system) : PluginImplBase(system) +{ + _parent->register_plugin(this); +} + +CameraServerImpl::~CameraServerImpl() +{ + _parent->unregister_plugin(this); +} + +void CameraServerImpl::init() +{ + _parent->register_mavlink_command_handler( + MAV_CMD_REQUEST_CAMERA_INFORMATION, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_camera_information_request(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_REQUEST_CAMERA_SETTINGS, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_camera_settings_request(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_REQUEST_STORAGE_INFORMATION, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_storage_information_request(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_STORAGE_FORMAT, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_storage_format(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_camera_capture_status_request(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_RESET_CAMERA_SETTINGS, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_reset_camera_settings(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_SET_CAMERA_MODE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_set_camera_mode(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_SET_CAMERA_ZOOM, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_set_camera_zoom(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_SET_CAMERA_FOCUS, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_set_camera_focus(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_SET_STORAGE_USAGE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_set_storage_usage(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_IMAGE_START_CAPTURE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_image_start_capture(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_IMAGE_STOP_CAPTURE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_image_stop_capture(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_camera_image_capture_request(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_DO_TRIGGER_CONTROL, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_do_trigger_control(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_VIDEO_START_CAPTURE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_video_start_capture(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_VIDEO_STOP_CAPTURE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_video_stop_capture(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_VIDEO_START_STREAMING, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_video_start_streaming(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_VIDEO_STOP_STREAMING, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_video_stop_streaming(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_video_stream_information_request(command); + }, + this); + _parent->register_mavlink_command_handler( + MAV_CMD_REQUEST_VIDEO_STREAM_STATUS, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_video_stream_status_request(command); + }, + this); +} + +void CameraServerImpl::deinit() {} + +void CameraServerImpl::enable() {} + +void CameraServerImpl::disable() {} + +CameraServer::Result CameraServerImpl::set_information(CameraServer::Information information) +{ + _is_information_set = true; + _information = information; + return CameraServer::Result::Success; +} + +CameraServer::Result CameraServerImpl::set_in_progress(bool in_progress) +{ + _in_progress = in_progress; + return CameraServer::Result::Success; +} + +void CameraServerImpl::subscribe_take_photo(CameraServer::TakePhotoCallback callback) +{ + UNUSED(callback); +} + +CameraServer::Result CameraServerImpl::publish_photo(CameraServer::CaptureInfo capture_info) +{ + UNUSED(capture_info); + + // TODO :) + return {}; +} + +std::optional CameraServerImpl::process_camera_information_request( + const MavlinkCommandReceiver::CommandLong& command) +{ + auto capabilities = static_cast(command.params.param1); + + if (!capabilities) { + LogDebug() << "early info return"; + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + } + + if (!_is_information_set) { + return _parent->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED); + } + + // ack needs to be sent before camera information message + auto ack_msg = _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + _parent->send_message(ack_msg); + LogDebug() << "sent info ack"; + + // FIXME: why is this needed to prevent dropping messages? + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + // unsupported items + const uint32_t firmware_version = 0; + const uint8_t lens_id = 0; + const uint16_t camera_definition_version = 0; + auto camera_definition_uri = ""; + + mavlink_message_t msg{}; + mavlink_msg_camera_information_pack( + _parent->get_own_system_id(), + _parent->get_own_component_id(), + &msg, + static_cast(_parent->get_time().elapsed_s() * 1e3), + reinterpret_cast(_information.vendor_name.c_str()), + reinterpret_cast(_information.model_name.c_str()), + firmware_version, + _information.focal_length_mm, + _information.horizontal_sensor_size_mm, + _information.vertical_sensor_size_mm, + _information.horizontal_resolution_px, + _information.vertical_resolution_px, + lens_id, + CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE, + camera_definition_version, + camera_definition_uri); + + _parent->send_message(msg); + LogDebug() << "sent info msg"; + + // ack was already sent + return std::nullopt; +} + +std::optional CameraServerImpl::process_camera_settings_request( + const MavlinkCommandReceiver::CommandLong& command) +{ + auto settings = static_cast(command.params.param1); + + if (!settings) { + LogDebug() << "early settings return"; + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + } + + // ack needs to be sent before camera information message + auto ack_msg = _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + _parent->send_message(ack_msg); + LogDebug() << "sent settings ack"; + + // FIXME: why is this needed to prevent dropping messages? + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + // unsupported + const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE; + const float zoom_level = 0; + const float focus_level = 0; + + mavlink_message_t msg{}; + mavlink_msg_camera_settings_pack( + _parent->get_own_system_id(), + _parent->get_own_component_id(), + &msg, + static_cast(_parent->get_time().elapsed_s() * 1e3), + mode_id, + zoom_level, + focus_level); + + _parent->send_message(msg); + LogDebug() << "sent settings msg"; + + // ack was already sent + return std::nullopt; +} + +std::optional CameraServerImpl::process_storage_information_request( + const MavlinkCommandReceiver::CommandLong& command) +{ + auto storage_id = static_cast(command.params.param1); + auto information = static_cast(command.params.param2); + + if (!information) { + LogDebug() << "early storage return"; + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + } + + // ack needs to be sent before camera information message + auto ack_msg = _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + _parent->send_message(ack_msg); + LogDebug() << "sent storage ack"; + + // FIXME: why is this needed to prevent dropping messages? + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + // unsupported + const uint8_t storage_count = 0; + const auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED; + const float total_capacity = 0; + const float used_capacity = 0; + const float available_capacity = 0; + const float read_speed = 0; + const float write_speed = 0; + const uint8_t type = STORAGE_TYPE::STORAGE_TYPE_UNKNOWN; + auto name = ""; + const uint8_t storage_usage = 0; + + mavlink_message_t msg{}; + mavlink_msg_storage_information_pack( + _parent->get_own_system_id(), + _parent->get_own_component_id(), + &msg, + static_cast(_parent->get_time().elapsed_s() * 1e3), + storage_id, + storage_count, + status, + total_capacity, + used_capacity, + available_capacity, + read_speed, + write_speed, + type, + name, + storage_usage); + + _parent->send_message(msg); + LogDebug() << "sent storage msg"; + + // ack was already sent + return std::nullopt; +} + +std::optional +CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command) +{ + auto storage_id = static_cast(command.params.param1); + auto format = static_cast(command.params.param2); + auto reset_image_log = static_cast(command.params.param3); + + UNUSED(storage_id); + UNUSED(format); + UNUSED(reset_image_log); + + LogDebug() << "unsupported storage format request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional CameraServerImpl::process_camera_capture_status_request( + const MavlinkCommandReceiver::CommandLong& command) +{ + auto capture_status = static_cast(command.params.param1); + + if (!capture_status) { + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + } + + // ack needs to be sent before camera information message + auto ack_msg = _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + _parent->send_message(ack_msg); + + // FIXME: why is this needed to prevent dropping messages? + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + uint8_t image_status{}; + if (_in_progress) { + image_status |= StatusFlags::IN_PROGRESS; + } + + int32_t image_count = 0; // TODO: get image capture vector length + + // unsupported + const uint8_t video_status = 0; + const float image_interval = 0; + const uint32_t recording_time_ms = 0; + const float available_capacity = 0; + + mavlink_message_t msg{}; + mavlink_msg_camera_capture_status_pack( + _parent->get_own_system_id(), + _parent->get_own_component_id(), + &msg, + static_cast(_parent->get_time().elapsed_s() * 1e3), + image_status, + video_status, + image_interval, + recording_time_ms, + available_capacity, + image_count); + + _parent->send_message(msg); + + // ack was already sent + return std::nullopt; +} + +std::optional +CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command) +{ + auto reset = static_cast(command.params.param1); + + UNUSED(reset); + + LogDebug() << "unsupported reset camera settings request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command) +{ + auto camera_mode = static_cast(command.params.param2); + + UNUSED(camera_mode); + + LogDebug() << "unsupported set camera mode request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command) +{ + auto zoom_type = static_cast(command.params.param1); + auto zoom_value = command.params.param2; + + UNUSED(zoom_type); + UNUSED(zoom_value); + + LogDebug() << "unsupported set camera zoom request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command) +{ + auto focus_type = static_cast(command.params.param1); + auto focus_value = command.params.param2; + + UNUSED(focus_type); + UNUSED(focus_value); + + LogDebug() << "unsupported set camera focus request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command) +{ + auto storage_id = static_cast(command.params.param1); + auto usage = static_cast(command.params.param2); + + UNUSED(storage_id); + UNUSED(usage); + + LogDebug() << "unsupported set storage usage request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command) +{ + auto interval = command.params.param2; + auto total_images = static_cast(command.params.param3); + auto seq_number = static_cast(command.params.param4); + + UNUSED(interval); + UNUSED(total_images); + UNUSED(seq_number); + + LogDebug() << "unsupported image start capture request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command) +{ + LogDebug() << "unsupported image stop capture request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional CameraServerImpl::process_camera_image_capture_request( + const MavlinkCommandReceiver::CommandLong& command) +{ + auto seq_number = static_cast(command.params.param1); + + UNUSED(seq_number); + + LogDebug() << "unsupported image capture request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_do_trigger_control(const MavlinkCommandReceiver::CommandLong& command) +{ + auto enable = static_cast(command.params.param1); + auto reset = static_cast(command.params.param2); + auto pause = static_cast(command.params.param3); + + UNUSED(enable); + UNUSED(reset); + UNUSED(pause); + + LogDebug() << "unsupported do trigger control request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command) +{ + auto stream_id = static_cast(command.params.param1); + auto status_frequency = command.params.param2; + + UNUSED(stream_id); + UNUSED(status_frequency); + + LogDebug() << "unsupported video start capture request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_video_stop_capture(const MavlinkCommandReceiver::CommandLong& command) +{ + auto stream_id = static_cast(command.params.param1); + + UNUSED(stream_id); + + LogDebug() << "unsupported video stop capture request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::CommandLong& command) +{ + auto stream_id = static_cast(command.params.param1); + + UNUSED(stream_id); + + LogDebug() << "unsupported video start streaming request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional +CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command) +{ + auto stream_id = static_cast(command.params.param1); + + UNUSED(stream_id); + + LogDebug() << "unsupported video stop streaming request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional CameraServerImpl::process_video_stream_information_request( + const MavlinkCommandReceiver::CommandLong& command) +{ + auto stream_id = static_cast(command.params.param1); + + UNUSED(stream_id); + + LogDebug() << "unsupported video stream information request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +std::optional CameraServerImpl::process_video_stream_status_request( + const MavlinkCommandReceiver::CommandLong& command) +{ + auto stream_id = static_cast(command.params.param1); + + UNUSED(stream_id); + + LogDebug() << "unsupported video stream status request"; + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); +} + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h new file mode 100644 index 0000000000..fc781bd1f4 --- /dev/null +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -0,0 +1,85 @@ +#pragma once + +#include "plugins/camera_server/camera_server.h" +#include "plugin_impl_base.h" + +namespace mavsdk { + +class CameraServerImpl : public PluginImplBase { +public: + explicit CameraServerImpl(System& system); + explicit CameraServerImpl(std::shared_ptr system); + ~CameraServerImpl(); + + void init() override; + void deinit() override; + + void enable() override; + void disable() override; + + CameraServer::Result set_information(CameraServer::Information information); + CameraServer::Result set_in_progress(bool in_progress); + + void subscribe_take_photo(CameraServer::TakePhotoCallback callback); + + CameraServer::Result publish_photo(CameraServer::CaptureInfo capture_info); + +private: + enum StatusFlags { + IN_PROGRESS = 1 << 0, + INTERVAL_SET = 1 << 1, + }; + + enum class TriggerControl { + IGNORE = -1, + DISABLE = 0, + ENABLE = 1, + }; + + bool _is_information_set{}; + CameraServer::Information _information{}; + bool _in_progress{}; + + std::optional + process_camera_information_request(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_camera_settings_request(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_storage_information_request(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_storage_format(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_camera_capture_status_request(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_camera_image_capture_request(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_do_trigger_control(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_video_stop_capture(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_video_start_streaming(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_video_stream_information_request(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_video_stream_status_request(const MavlinkCommandReceiver::CommandLong& command); +}; + +} // namespace mavsdk \ No newline at end of file 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 new file mode 100644 index 0000000000..d69a407dd3 --- /dev/null +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -0,0 +1,294 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see https://github.com/mavlink/MAVSDK-Proto/blob/main/protos/camera_server/camera_server.proto) + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "mavsdk/plugin_base.h" + +namespace mavsdk { + +class System; +class CameraServerImpl; + +/** + * @brief Provides handling of camera trigger commands. + */ +class CameraServer : public PluginBase { +public: + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto camera_server = CameraServer(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit CameraServer(System& system); // deprecated + + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto camera_server = CameraServer(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit CameraServer(std::shared_ptr system); // new + + /** + * @brief Destructor (internal use only). + */ + ~CameraServer(); + + + + + + /** + * @brief Type to represent a camera information. + */ + struct Information { + + std::string vendor_name{}; /**< @brief Name of the camera vendor */ + std::string model_name{}; /**< @brief Name of the camera model */ + float focal_length_mm{}; /**< @brief Focal length */ + float horizontal_sensor_size_mm{}; /**< @brief Horizontal sensor size */ + float vertical_sensor_size_mm{}; /**< @brief Vertical sensor size */ + uint32_t horizontal_resolution_px{}; /**< @brief Horizontal image resolution in pixels */ + uint32_t vertical_resolution_px{}; /**< @brief Vertical image resolution in pixels */ + }; + + /** + * @brief Equal operator to compare two `CameraServer::Information` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs); + + /** + * @brief Stream operator to print information about a `CameraServer::Information`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information); + + + + + /** + * @brief Position type in global coordinates. + */ + struct Position { + + double latitude_deg{}; /**< @brief Latitude in degrees (range: -90 to +90) */ + double longitude_deg{}; /**< @brief Longitude in degrees (range: -180 to +180) */ + float absolute_altitude_m{}; /**< @brief Altitude AMSL (above mean sea level) in metres */ + float relative_altitude_m{}; /**< @brief Altitude relative to takeoff altitude in metres */ + }; + + /** + * @brief Equal operator to compare two `CameraServer::Position` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const CameraServer::Position& lhs, const CameraServer::Position& rhs); + + /** + * @brief Stream operator to print information about a `CameraServer::Position`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, CameraServer::Position const& position); + + + + + /** + * @brief Quaternion type. + * + * All rotations and axis systems follow the right-hand rule. + * The Hamilton quaternion product definition is used. + * A zero-rotation quaternion is represented by (1,0,0,0). + * The quaternion could also be written as w + xi + yj + zk. + * + * For more info see: https://en.wikipedia.org/wiki/Quaternion + */ + struct Quaternion { + + float w{}; /**< @brief Quaternion entry 0, also denoted as a */ + float x{}; /**< @brief Quaternion entry 1, also denoted as b */ + float y{}; /**< @brief Quaternion entry 2, also denoted as c */ + float z{}; /**< @brief Quaternion entry 3, also denoted as d */ + }; + + /** + * @brief Equal operator to compare two `CameraServer::Quaternion` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const CameraServer::Quaternion& lhs, const CameraServer::Quaternion& rhs); + + /** + * @brief Stream operator to print information about a `CameraServer::Quaternion`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, CameraServer::Quaternion const& quaternion); + + + + + /** + * @brief Information about a picture just captured. + */ + struct CaptureInfo { + + Position position{}; /**< @brief Location where the picture was taken */ + Quaternion attitude_quaternion{}; /**< @brief Attitude of the camera when the picture was taken (quaternion) */ + uint64_t time_utc_us{}; /**< @brief Timestamp in UTC (since UNIX epoch) in microseconds */ + bool is_success{}; /**< @brief True if the capture was successful */ + int32_t index{}; /**< @brief Index from TakePhotoResponse */ + std::string file_url{}; /**< @brief Download URL of this image */ + }; + + /** + * @brief Equal operator to compare two `CameraServer::CaptureInfo` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const CameraServer::CaptureInfo& lhs, const CameraServer::CaptureInfo& rhs); + + /** + * @brief Stream operator to print information about a `CameraServer::CaptureInfo`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, CameraServer::CaptureInfo const& capture_info); + + + + + + /** + * @brief Possible results returned for action requests. + */ + enum class Result { + Unknown, /**< @brief Unknown result. */ + Success, /**< @brief Command executed successfully. */ + InProgress, /**< @brief Command in progress. */ + Busy, /**< @brief Camera is busy and rejected command. */ + Denied, /**< @brief Camera denied the command. */ + Error, /**< @brief An error has occurred while executing the command. */ + Timeout, /**< @brief Command timed out. */ + WrongArgument, /**< @brief Command has wrong argument(s). */ + NoSystem, /**< @brief No system connected. */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::Result`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, CameraServer::Result const& result); + + + + /** + * @brief Callback type for asynchronous CameraServer calls. + */ + using ResultCallback = std::function; + + + + + + + /** + * @brief Sets the camera information + * + * This function is blocking. + * + * @return Result of request. + */ + Result set_information(Information information) const; + + + + + + + /** + * @brief Sets the camera capture status + * + * This function is blocking. + * + * @return Result of request. + */ + Result set_in_progress(bool in_progress) const; + + + + + + /** + * @brief Callback type for subscribe_take_photo. + */ + + using TakePhotoCallback = std::function; + + /** + * @brief Subscribe to single-image capture commands + */ + void subscribe_take_photo(TakePhotoCallback callback); + + + + + + + + + /** + * @brief Adds a photo to the list of available photos + * + * This function is blocking. + * + * @return Result of request. + */ + Result publish_photo(CaptureInfo capture_info) const; + + + + + /** + * @brief Copy constructor. + */ + CameraServer(const CameraServer& other); + + /** + * @brief Equality operator (object is not copyable). + */ + const CameraServer& operator=(const CameraServer&) = delete; + +private: + /** @private Underlying implementation, set at instantiation */ + std::unique_ptr _impl; +}; + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk_server/src/CMakeLists.txt b/src/mavsdk_server/src/CMakeLists.txt index 325bbc0437..00f281f9a8 100644 --- a/src/mavsdk_server/src/CMakeLists.txt +++ b/src/mavsdk_server/src/CMakeLists.txt @@ -5,6 +5,7 @@ set(COMPONENTS_LIST action_server calibration camera + camera_server core failure follow_me 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 new file mode 100644 index 0000000000..6b5cbf4fda --- /dev/null +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -0,0 +1,209 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: camera_server/camera_server.proto + +#include "camera_server/camera_server.pb.h" +#include "camera_server/camera_server.grpc.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +namespace mavsdk { +namespace rpc { +namespace camera_server { + +static const char* CameraServerService_method_names[] = { + "/mavsdk.rpc.camera_server.CameraServerService/SetInformation", + "/mavsdk.rpc.camera_server.CameraServerService/SetInProgress", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", + "/mavsdk.rpc.camera_server.CameraServerService/PublishPhoto", +}; + +std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { + (void)options; + std::unique_ptr< CameraServerService::Stub> stub(new CameraServerService::Stub(channel, options)); + return stub; +} + +CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) + : channel_(channel), rpcmethod_SetInformation_(CameraServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetInProgress_(CameraServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeTakePhoto_(CameraServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_PublishPhoto_(CameraServerService_method_names[3], 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) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::SetInformationRequest, ::mavsdk::rpc::camera_server::SetInformationResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetInformation_, context, request, response); +} + +void CameraServerService::Stub::async::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::SetInformationRequest, ::mavsdk::rpc::camera_server::SetInformationResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetInformation_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetInformation_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>* CameraServerService::Stub::PrepareAsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::SetInformationResponse, ::mavsdk::rpc::camera_server::SetInformationRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetInformation_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>* CameraServerService::Stub::AsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncSetInformationRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraServerService::Stub::SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetInProgress_, context, request, response); +} + +void CameraServerService::Stub::async::SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetInProgress_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetInProgress_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>* CameraServerService::Stub::PrepareAsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::SetInProgressResponse, ::mavsdk::rpc::camera_server::SetInProgressRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetInProgress_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>* CameraServerService::Stub::AsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncSetInProgressRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::ClientReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* CameraServerService::Stub::SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::TakePhotoResponse>::Create(channel_.get(), rpcmethod_SubscribeTakePhoto_, context, request); +} + +void CameraServerService::Stub::async::SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::TakePhotoResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeTakePhoto_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* CameraServerService::Stub::AsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::TakePhotoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeTakePhoto_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* CameraServerService::Stub::PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::TakePhotoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeTakePhoto_, context, request, false, nullptr); +} + +::grpc::Status CameraServerService::Stub::PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_PublishPhoto_, context, request, response); +} + +void CameraServerService::Stub::async::PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_PublishPhoto_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_PublishPhoto_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* CameraServerService::Stub::PrepareAsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::PublishPhotoResponse, ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_PublishPhoto_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* CameraServerService::Stub::AsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncPublishPhotoRaw(context, request, cq); + result->StartCall(); + return result; +} + +CameraServerService::Service::Service() { + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[0], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SetInformationRequest, ::mavsdk::rpc::camera_server::SetInformationResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SetInformationRequest* req, + ::mavsdk::rpc::camera_server::SetInformationResponse* resp) { + return service->SetInformation(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[1], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SetInProgressRequest* req, + ::mavsdk::rpc::camera_server::SetInProgressResponse* resp) { + return service->SetInProgress(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[2], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest, ::mavsdk::rpc::camera_server::TakePhotoResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::TakePhotoResponse>* writer) { + return service->SubscribeTakePhoto(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[3], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::PublishPhotoRequest* req, + ::mavsdk::rpc::camera_server::PublishPhotoResponse* resp) { + return service->PublishPhoto(ctx, req, resp); + }, this))); +} + +CameraServerService::Service::~Service() { +} + +::grpc::Status CameraServerService::Service::SetInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SetInProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::PublishPhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + + +} // namespace mavsdk +} // namespace rpc +} // namespace camera_server + 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 new file mode 100644 index 0000000000..24909863fe --- /dev/null +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -0,0 +1,727 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: camera_server/camera_server.proto +#ifndef GRPC_camera_5fserver_2fcamera_5fserver_2eproto__INCLUDED +#define GRPC_camera_5fserver_2fcamera_5fserver_2eproto__INCLUDED + +#include "camera_server/camera_server.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace rpc { +namespace camera_server { + +// Provides handling of camera trigger commands. +class CameraServerService final { + public: + static constexpr char const* service_full_name() { + return "mavsdk.rpc.camera_server.CameraServerService"; + } + class StubInterface { + public: + virtual ~StubInterface() {} + // Sets the camera information + virtual ::grpc::Status SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>> AsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>>(AsyncSetInformationRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>> PrepareAsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>>(PrepareAsyncSetInformationRaw(context, request, cq)); + } + // Sets the camera capture status + virtual ::grpc::Status SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>> AsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(AsyncSetInProgressRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>> PrepareAsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(PrepareAsyncSetInProgressRaw(context, request, cq)); + } + // Subscribe to single-image capture commands + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>> SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(SubscribeTakePhotoRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>> AsyncSubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(AsyncSubscribeTakePhotoRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>> PrepareAsyncSubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(PrepareAsyncSubscribeTakePhotoRaw(context, request, cq)); + } + // Adds a photo to the list of available photos + virtual ::grpc::Status PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>> AsyncPublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>>(AsyncPublishPhotoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>> PrepareAsyncPublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>>(PrepareAsyncPublishPhotoRaw(context, request, cq)); + } + class async_interface { + public: + virtual ~async_interface() {} + // Sets the camera information + virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function) = 0; + virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Sets the camera capture status + virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) = 0; + virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to single-image capture commands + virtual void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) = 0; + // Adds a photo to the list of available photos + virtual void PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, std::function) = 0; + virtual void PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + }; + typedef class async_interface experimental_async_interface; + virtual class async_interface* async() { return nullptr; } + class async_interface* experimental_async() { return async(); } + private: + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>* AsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>* PrepareAsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>* AsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>* PrepareAsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* AsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* AsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* PrepareAsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; + }; + class Stub final : public StubInterface { + public: + Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + ::grpc::Status SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>> AsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>>(AsyncSetInformationRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>> PrepareAsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>>(PrepareAsyncSetInformationRaw(context, request, cq)); + } + ::grpc::Status SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>> AsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(AsyncSetInProgressRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>> PrepareAsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(PrepareAsyncSetInProgressRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>> SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(SubscribeTakePhotoRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>> AsyncSubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(AsyncSubscribeTakePhotoRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>> PrepareAsyncSubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(PrepareAsyncSubscribeTakePhotoRaw(context, request, cq)); + } + ::grpc::Status PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>> AsyncPublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>>(AsyncPublishPhotoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>> PrepareAsyncPublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>>(PrepareAsyncPublishPhotoRaw(context, request, cq)); + } + class async final : + public StubInterface::async_interface { + public: + void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function) override; + void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) override; + void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) override; + void PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, std::function) override; + void PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + private: + friend class Stub; + explicit async(Stub* stub): stub_(stub) { } + Stub* stub() { return stub_; } + Stub* stub_; + }; + class async* async() override { return &async_stub_; } + + private: + std::shared_ptr< ::grpc::ChannelInterface> channel_; + class async async_stub_{this}; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>* AsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>* PrepareAsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>* AsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>* PrepareAsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* AsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* AsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* PrepareAsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) override; + const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; + const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; + const ::grpc::internal::RpcMethod rpcmethod_PublishPhoto_; + }; + static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + + class Service : public ::grpc::Service { + public: + Service(); + virtual ~Service(); + // Sets the camera information + virtual ::grpc::Status SetInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response); + // Sets the camera capture status + virtual ::grpc::Status SetInProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response); + // Subscribe to single-image capture commands + virtual ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer); + // Adds a photo to the list of available photos + virtual ::grpc::Status PublishPhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response); + }; + template + class WithAsyncMethod_SetInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SetInformation() { + ::grpc::Service::MarkMethodAsync(0); + } + ~WithAsyncMethod_SetInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetInformation(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::SetInformationResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SetInProgress : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SetInProgress() { + ::grpc::Service::MarkMethodAsync(1); + } + ~WithAsyncMethod_SetInProgress() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInProgress(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInProgressRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInProgressResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetInProgress(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::SetInProgressResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeTakePhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeTakePhoto() { + ::grpc::Service::MarkMethodAsync(2); + } + ~WithAsyncMethod_SubscribeTakePhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeTakePhoto(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(2, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_PublishPhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_PublishPhoto() { + ::grpc::Service::MarkMethodAsync(3); + } + ~WithAsyncMethod_PublishPhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestPublishPhoto(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetInformation > > > AsyncService; + template + class WithCallbackMethod_SetInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SetInformation() { + ::grpc::Service::MarkMethodCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetInformationRequest, ::mavsdk::rpc::camera_server::SetInformationResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { return this->SetInformation(context, request, response); }));} + void SetMessageAllocatorFor_SetInformation( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::SetInformationRequest, ::mavsdk::rpc::camera_server::SetInformationResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetInformationRequest, ::mavsdk::rpc::camera_server::SetInformationResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_SetInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetInformation( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_SetInProgress : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SetInProgress() { + ::grpc::Service::MarkMethodCallback(1, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) { return this->SetInProgress(context, request, response); }));} + void SetMessageAllocatorFor_SetInProgress( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_SetInProgress() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInProgress(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInProgressRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInProgressResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetInProgress( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInProgressRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInProgressResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeTakePhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeTakePhoto() { + ::grpc::Service::MarkMethodCallback(2, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest, ::mavsdk::rpc::camera_server::TakePhotoResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request) { return this->SubscribeTakePhoto(context, request); })); + } + ~WithCallbackMethod_SubscribeTakePhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhoto( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_PublishPhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_PublishPhoto() { + ::grpc::Service::MarkMethodCallback(3, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) { return this->PublishPhoto(context, request, response); }));} + void SetMessageAllocatorFor_PublishPhoto( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_PublishPhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* PublishPhoto( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetInformation > > > CallbackService; + typedef CallbackService ExperimentalCallbackService; + template + class WithGenericMethod_SetInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetInformation() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_SetInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SetInProgress : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetInProgress() { + ::grpc::Service::MarkMethodGeneric(1); + } + ~WithGenericMethod_SetInProgress() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInProgress(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInProgressRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInProgressResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeTakePhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeTakePhoto() { + ::grpc::Service::MarkMethodGeneric(2); + } + ~WithGenericMethod_SubscribeTakePhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_PublishPhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_PublishPhoto() { + ::grpc::Service::MarkMethodGeneric(3); + } + ~WithGenericMethod_PublishPhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*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 + ::grpc::Status SetInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetInformation(::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(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SetInProgress : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetInProgress() { + ::grpc::Service::MarkMethodRaw(1); + } + ~WithRawMethod_SetInProgress() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInProgress(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInProgressRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInProgressResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetInProgress(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeTakePhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeTakePhoto() { + ::grpc::Service::MarkMethodRaw(2); + } + ~WithRawMethod_SubscribeTakePhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeTakePhoto(::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(2, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_PublishPhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_PublishPhoto() { + ::grpc::Service::MarkMethodRaw(3); + } + ~WithRawMethod_PublishPhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestPublishPhoto(::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(3, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawCallbackMethod_SetInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetInformation() { + ::grpc::Service::MarkMethodRawCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetInformation(context, request, response); })); + } + ~WithRawCallbackMethod_SetInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetInformation( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SetInProgress : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetInProgress() { + ::grpc::Service::MarkMethodRawCallback(1, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetInProgress(context, request, response); })); + } + ~WithRawCallbackMethod_SetInProgress() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetInProgress(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInProgressRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInProgressResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetInProgress( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeTakePhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeTakePhoto() { + ::grpc::Service::MarkMethodRawCallback(2, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeTakePhoto(context, request); })); + } + ~WithRawCallbackMethod_SubscribeTakePhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeTakePhoto( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_PublishPhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_PublishPhoto() { + ::grpc::Service::MarkMethodRawCallback(3, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->PublishPhoto(context, request, response); })); + } + ~WithRawCallbackMethod_PublishPhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* PublishPhoto( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithStreamedUnaryMethod_SetInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_SetInformation() { + ::grpc::Service::MarkMethodStreamed(0, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::SetInformationRequest, ::mavsdk::rpc::camera_server::SetInformationResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::SetInformationRequest, ::mavsdk::rpc::camera_server::SetInformationResponse>* streamer) { + return this->StreamedSetInformation(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_SetInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SetInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedSetInformation(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::SetInformationRequest,::mavsdk::rpc::camera_server::SetInformationResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_SetInProgress : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_SetInProgress() { + ::grpc::Service::MarkMethodStreamed(1, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>* streamer) { + return this->StreamedSetInProgress(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_SetInProgress() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SetInProgress(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInProgressRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInProgressResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedSetInProgress(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::SetInProgressRequest,::mavsdk::rpc::camera_server::SetInProgressResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_PublishPhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_PublishPhoto() { + ::grpc::Service::MarkMethodStreamed(3, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>* streamer) { + return this->StreamedPublishPhoto(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_PublishPhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedPublishPhoto(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::PublishPhotoRequest,::mavsdk::rpc::camera_server::PublishPhotoResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_SetInformation > > StreamedUnaryService; + template + class WithSplitStreamingMethod_SubscribeTakePhoto : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeTakePhoto() { + ::grpc::Service::MarkMethodStreamed(2, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest, ::mavsdk::rpc::camera_server::TakePhotoResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest, ::mavsdk::rpc::camera_server::TakePhotoResponse>* streamer) { + return this->StreamedSubscribeTakePhoto(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeTakePhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeTakePhoto(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest,::mavsdk::rpc::camera_server::TakePhotoResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeTakePhoto SplitStreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > StreamedService; +}; + +} // namespace camera_server +} // namespace rpc +} // namespace mavsdk + + +#endif // GRPC_camera_5fserver_2fcamera_5fserver_2eproto__INCLUDED 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 new file mode 100644 index 0000000000..82c9875186 --- /dev/null +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -0,0 +1,3537 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: camera_server/camera_server.proto + +#include "camera_server/camera_server.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +// @@protoc_insertion_point(includes) +#include + +PROTOBUF_PRAGMA_INIT_SEG +namespace mavsdk { +namespace rpc { +namespace camera_server { +constexpr SetInformationRequest::SetInformationRequest( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : information_(nullptr){} +struct SetInformationRequestDefaultTypeInternal { + constexpr SetInformationRequestDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~SetInformationRequestDefaultTypeInternal() {} + union { + SetInformationRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT SetInformationRequestDefaultTypeInternal _SetInformationRequest_default_instance_; +constexpr SetInformationResponse::SetInformationResponse( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : camera_server_result_(nullptr){} +struct SetInformationResponseDefaultTypeInternal { + constexpr SetInformationResponseDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~SetInformationResponseDefaultTypeInternal() {} + union { + SetInformationResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT SetInformationResponseDefaultTypeInternal _SetInformationResponse_default_instance_; +constexpr SetInProgressRequest::SetInProgressRequest( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : in_progress_(false){} +struct SetInProgressRequestDefaultTypeInternal { + constexpr SetInProgressRequestDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~SetInProgressRequestDefaultTypeInternal() {} + union { + SetInProgressRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT SetInProgressRequestDefaultTypeInternal _SetInProgressRequest_default_instance_; +constexpr SetInProgressResponse::SetInProgressResponse( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : camera_server_result_(nullptr){} +struct SetInProgressResponseDefaultTypeInternal { + constexpr SetInProgressResponseDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~SetInProgressResponseDefaultTypeInternal() {} + union { + SetInProgressResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT SetInProgressResponseDefaultTypeInternal _SetInProgressResponse_default_instance_; +constexpr SubscribeTakePhotoRequest::SubscribeTakePhotoRequest( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized){} +struct SubscribeTakePhotoRequestDefaultTypeInternal { + constexpr SubscribeTakePhotoRequestDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~SubscribeTakePhotoRequestDefaultTypeInternal() {} + union { + SubscribeTakePhotoRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_default_instance_; +constexpr TakePhotoResponse::TakePhotoResponse( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : camera_server_result_(nullptr) + , index_(0){} +struct TakePhotoResponseDefaultTypeInternal { + constexpr TakePhotoResponseDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~TakePhotoResponseDefaultTypeInternal() {} + union { + TakePhotoResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; +constexpr PublishPhotoRequest::PublishPhotoRequest( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : capture_info_(nullptr){} +struct PublishPhotoRequestDefaultTypeInternal { + constexpr PublishPhotoRequestDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~PublishPhotoRequestDefaultTypeInternal() {} + union { + PublishPhotoRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PublishPhotoRequestDefaultTypeInternal _PublishPhotoRequest_default_instance_; +constexpr PublishPhotoResponse::PublishPhotoResponse( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : camera_server_result_(nullptr){} +struct PublishPhotoResponseDefaultTypeInternal { + constexpr PublishPhotoResponseDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~PublishPhotoResponseDefaultTypeInternal() {} + union { + PublishPhotoResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PublishPhotoResponseDefaultTypeInternal _PublishPhotoResponse_default_instance_; +constexpr Information::Information( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : vendor_name_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , model_name_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , focal_length_mm_(0) + , horizontal_sensor_size_mm_(0) + , vertical_sensor_size_mm_(0) + , horizontal_resolution_px_(0u) + , vertical_resolution_px_(0u){} +struct InformationDefaultTypeInternal { + constexpr InformationDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~InformationDefaultTypeInternal() {} + union { + Information _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT InformationDefaultTypeInternal _Information_default_instance_; +constexpr Position::Position( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : latitude_deg_(0) + , longitude_deg_(0) + , absolute_altitude_m_(0) + , relative_altitude_m_(0){} +struct PositionDefaultTypeInternal { + constexpr PositionDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~PositionDefaultTypeInternal() {} + union { + Position _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PositionDefaultTypeInternal _Position_default_instance_; +constexpr Quaternion::Quaternion( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : w_(0) + , x_(0) + , y_(0) + , z_(0){} +struct QuaternionDefaultTypeInternal { + constexpr QuaternionDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~QuaternionDefaultTypeInternal() {} + union { + Quaternion _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT QuaternionDefaultTypeInternal _Quaternion_default_instance_; +constexpr CaptureInfo::CaptureInfo( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : file_url_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , position_(nullptr) + , attitude_quaternion_(nullptr) + , time_utc_us_(uint64_t{0u}) + , is_success_(false) + , index_(0){} +struct CaptureInfoDefaultTypeInternal { + constexpr CaptureInfoDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~CaptureInfoDefaultTypeInternal() {} + union { + CaptureInfo _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT CaptureInfoDefaultTypeInternal _CaptureInfo_default_instance_; +constexpr CameraServerResult::CameraServerResult( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : result_str_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , result_(0) +{} +struct CameraServerResultDefaultTypeInternal { + constexpr CameraServerResultDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~CameraServerResultDefaultTypeInternal() {} + union { + CameraServerResult _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT CameraServerResultDefaultTypeInternal _CameraServerResult_default_instance_; +} // namespace camera_server +} // namespace rpc +} // namespace mavsdk +static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]; +static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[1]; +static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; + +const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInformationRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInformationRequest, information_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInformationResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInformationResponse, camera_server_result_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInProgressRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInProgressRequest, in_progress_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInProgressResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInProgressResponse, camera_server_result_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::TakePhotoResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::TakePhotoResponse, camera_server_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::TakePhotoResponse, index_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::PublishPhotoRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::PublishPhotoRequest, capture_info_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::PublishPhotoResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::PublishPhotoResponse, camera_server_result_), + ~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_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vendor_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, model_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, focal_length_mm_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, horizontal_sensor_size_mm_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vertical_sensor_size_mm_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, horizontal_resolution_px_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vertical_resolution_px_), + ~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_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, latitude_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, longitude_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, absolute_altitude_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, 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_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, w_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, x_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, y_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Quaternion, z_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, position_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, attitude_quaternion_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, time_utc_us_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, is_success_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, index_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureInfo, file_url_), + ~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_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CameraServerResult, result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CameraServerResult, result_str_), +}; +static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::mavsdk::rpc::camera_server::SetInformationRequest)}, + { 6, -1, sizeof(::mavsdk::rpc::camera_server::SetInformationResponse)}, + { 12, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressRequest)}, + { 18, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, + { 24, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, + { 29, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, + { 36, -1, sizeof(::mavsdk::rpc::camera_server::PublishPhotoRequest)}, + { 42, -1, sizeof(::mavsdk::rpc::camera_server::PublishPhotoResponse)}, + { 48, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 60, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 69, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 78, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 89, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, +}; + +static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = { + reinterpret_cast(&::mavsdk::rpc::camera_server::_SetInformationRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_SetInformationResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_SetInProgressRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_SetInProgressResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_SubscribeTakePhotoRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_TakePhotoResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_PublishPhotoRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_PublishPhotoResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_Information_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_Position_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_Quaternion_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_), +}; + +const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = + "\n!camera_server/camera_server.proto\022\030mav" + "sdk.rpc.camera_server\032\024mavsdk_options.pr" + "oto\"S\n\025SetInformationRequest\022:\n\013informat" + "ion\030\001 \001(\0132%.mavsdk.rpc.camera_server.Inf" + "ormation\"d\n\026SetInformationResponse\022J\n\024ca" + "mera_server_result\030\001 \001(\0132,.mavsdk.rpc.ca" + "mera_server.CameraServerResult\"+\n\024SetInP" + "rogressRequest\022\023\n\013in_progress\030\001 \001(\010\"c\n\025S" + "etInProgressResponse\022J\n\024camera_server_re" + "sult\030\001 \001(\0132,.mavsdk.rpc.camera_server.Ca" + "meraServerResult\"\033\n\031SubscribeTakePhotoRe" + "quest\"n\n\021TakePhotoResponse\022J\n\024camera_ser" + "ver_result\030\001 \001(\0132,.mavsdk.rpc.camera_ser" + "ver.CameraServerResult\022\r\n\005index\030\002 \001(\005\"R\n" + "\023PublishPhotoRequest\022;\n\014capture_info\030\001 \001" + "(\0132%.mavsdk.rpc.camera_server.CaptureInf" + "o\"b\n\024PublishPhotoResponse\022J\n\024camera_serv" + "er_result\030\001 \001(\0132,.mavsdk.rpc.camera_serv" + "er.CameraServerResult\"\325\001\n\013Information\022\023\n" + "\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\027" + "\n\017focal_length_mm\030\003 \001(\002\022!\n\031horizontal_se" + "nsor_size_mm\030\004 \001(\002\022\037\n\027vertical_sensor_si" + "ze_mm\030\005 \001(\002\022 \n\030horizontal_resolution_px\030" + "\006 \001(\r\022\036\n\026vertical_resolution_px\030\007 \001(\r\"q\n" + "\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongi" + "tude_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\nQuat" + "ernion\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\023attitude_quaternion\030\002 \001(\0132$.mavsdk.r" + "pc.camera_server.Quaternion\022\023\n\013time_utc_" + "us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 " + "\001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022CameraServerRe" + "sult\022C\n\006result\030\001 \001(\01623.mavsdk.rpc.camera" + "_server.CameraServerResult.Result\022\022\n\nres" + "ult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNO" + "WN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PR" + "OGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENI" + "ED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT" + "\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_" + "NO_SYSTEM\020\0102\375\003\n\023CameraServerService\022y\n\016S" + "etInformation\022/.mavsdk.rpc.camera_server" + ".SetInformationRequest\0320.mavsdk.rpc.came" + "ra_server.SetInformationResponse\"\004\200\265\030\001\022v" + "\n\rSetInProgress\022..mavsdk.rpc.camera_serv" + "er.SetInProgressRequest\032/.mavsdk.rpc.cam" + "era_server.SetInProgressResponse\"\004\200\265\030\001\022~" + "\n\022SubscribeTakePhoto\0223.mavsdk.rpc.camera" + "_server.SubscribeTakePhotoRequest\032+.mavs" + "dk.rpc.camera_server.TakePhotoResponse\"\004" + "\200\265\030\0000\001\022s\n\014PublishPhoto\022-.mavsdk.rpc.came" + "ra_server.PublishPhotoRequest\032..mavsdk.r" + "pc.camera_server.PublishPhotoResponse\"\004\200" + "\265\030\001B,\n\027io.mavsdk.camera_serverB\021CameraSe" + "rverProtob\006proto3" + ; +static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { + &::descriptor_table_mavsdk_5foptions_2eproto, +}; +static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once; +const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { + false, false, 2217, 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, 13, + schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto, file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto, file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto, +}; +PROTOBUF_ATTRIBUTE_WEAK const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable* descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter() { + return &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto; +} + +// Force running AddDescriptors() at dynamic initialization time. +PROTOBUF_ATTRIBUTE_INIT_PRIORITY static ::PROTOBUF_NAMESPACE_ID::internal::AddDescriptorsRunner dynamic_init_dummy_camera_5fserver_2fcamera_5fserver_2eproto(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); +namespace mavsdk { +namespace rpc { +namespace camera_server { +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* CameraServerResult_Result_descriptor() { + ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[0]; +} +bool CameraServerResult_Result_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + case 8: + return true; + default: + return false; + } +} + +#if (__cplusplus < 201703) && (!defined(_MSC_VER) || _MSC_VER >= 1900) +constexpr CameraServerResult_Result CameraServerResult::RESULT_UNKNOWN; +constexpr CameraServerResult_Result CameraServerResult::RESULT_SUCCESS; +constexpr CameraServerResult_Result CameraServerResult::RESULT_IN_PROGRESS; +constexpr CameraServerResult_Result CameraServerResult::RESULT_BUSY; +constexpr CameraServerResult_Result CameraServerResult::RESULT_DENIED; +constexpr CameraServerResult_Result CameraServerResult::RESULT_ERROR; +constexpr CameraServerResult_Result CameraServerResult::RESULT_TIMEOUT; +constexpr CameraServerResult_Result CameraServerResult::RESULT_WRONG_ARGUMENT; +constexpr CameraServerResult_Result CameraServerResult::RESULT_NO_SYSTEM; +constexpr CameraServerResult_Result CameraServerResult::Result_MIN; +constexpr CameraServerResult_Result CameraServerResult::Result_MAX; +constexpr int CameraServerResult::Result_ARRAYSIZE; +#endif // (__cplusplus < 201703) && (!defined(_MSC_VER) || _MSC_VER >= 1900) + +// =================================================================== + +class SetInformationRequest::_Internal { + public: + static const ::mavsdk::rpc::camera_server::Information& information(const SetInformationRequest* msg); +}; + +const ::mavsdk::rpc::camera_server::Information& +SetInformationRequest::_Internal::information(const SetInformationRequest* msg) { + return *msg->information_; +} +SetInformationRequest::SetInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetInformationRequest) +} +SetInformationRequest::SetInformationRequest(const SetInformationRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_information()) { + information_ = new ::mavsdk::rpc::camera_server::Information(*from.information_); + } else { + information_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetInformationRequest) +} + +inline void SetInformationRequest::SharedCtor() { +information_ = nullptr; +} + +SetInformationRequest::~SetInformationRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetInformationRequest) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void SetInformationRequest::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete information_; +} + +void SetInformationRequest::ArenaDtor(void* object) { + SetInformationRequest* _this = reinterpret_cast< SetInformationRequest* >(object); + (void)_this; +} +void SetInformationRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void SetInformationRequest::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SetInformationRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetInformationRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && information_ != nullptr) { + delete information_; + } + information_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetInformationRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.Information information = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_information(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* SetInformationRequest::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetInformationRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.Information information = 1; + if (this->_internal_has_information()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::information(this), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SetInformationRequest) + return target; +} + +size_t SetInformationRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetInformationRequest) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.Information information = 1; + if (this->_internal_has_information()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *information_); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetInformationRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SetInformationRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetInformationRequest::GetClassData() const { return &_class_data_; } + +void SetInformationRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SetInformationRequest::MergeFrom(const SetInformationRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SetInformationRequest) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_information()) { + _internal_mutable_information()->::mavsdk::rpc::camera_server::Information::MergeFrom(from._internal_information()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetInformationRequest::CopyFrom(const SetInformationRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetInformationRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetInformationRequest::IsInitialized() const { + return true; +} + +void SetInformationRequest::InternalSwap(SetInformationRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(information_, other->information_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetInformationRequest::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[0]); +} + +// =================================================================== + +class SetInformationResponse::_Internal { + public: + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const SetInformationResponse* msg); +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +SetInformationResponse::_Internal::camera_server_result(const SetInformationResponse* msg) { + return *msg->camera_server_result_; +} +SetInformationResponse::SetInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetInformationResponse) +} +SetInformationResponse::SetInformationResponse(const SetInformationResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_camera_server_result()) { + camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from.camera_server_result_); + } else { + camera_server_result_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetInformationResponse) +} + +inline void SetInformationResponse::SharedCtor() { +camera_server_result_ = nullptr; +} + +SetInformationResponse::~SetInformationResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetInformationResponse) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void SetInformationResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete camera_server_result_; +} + +void SetInformationResponse::ArenaDtor(void* object) { + SetInformationResponse* _this = reinterpret_cast< SetInformationResponse* >(object); + (void)_this; +} +void SetInformationResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void SetInformationResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SetInformationResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetInformationResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { + delete camera_server_result_; + } + camera_server_result_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetInformationResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* SetInformationResponse::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetInformationResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (this->_internal_has_camera_server_result()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::camera_server_result(this), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SetInformationResponse) + return target; +} + +size_t SetInformationResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetInformationResponse) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 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; + if (this->_internal_has_camera_server_result()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *camera_server_result_); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetInformationResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SetInformationResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetInformationResponse::GetClassData() const { return &_class_data_; } + +void SetInformationResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SetInformationResponse::MergeFrom(const SetInformationResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SetInformationResponse) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_camera_server_result()) { + _internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom(from._internal_camera_server_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetInformationResponse::CopyFrom(const SetInformationResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetInformationResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetInformationResponse::IsInitialized() const { + return true; +} + +void SetInformationResponse::InternalSwap(SetInformationResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(camera_server_result_, other->camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetInformationResponse::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[1]); +} + +// =================================================================== + +class SetInProgressRequest::_Internal { + public: +}; + +SetInProgressRequest::SetInProgressRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetInProgressRequest) +} +SetInProgressRequest::SetInProgressRequest(const SetInProgressRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + in_progress_ = from.in_progress_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetInProgressRequest) +} + +inline void SetInProgressRequest::SharedCtor() { +in_progress_ = false; +} + +SetInProgressRequest::~SetInProgressRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetInProgressRequest) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void SetInProgressRequest::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); +} + +void SetInProgressRequest::ArenaDtor(void* object) { + SetInProgressRequest* _this = reinterpret_cast< SetInProgressRequest* >(object); + (void)_this; +} +void SetInProgressRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void SetInProgressRequest::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SetInProgressRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetInProgressRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + in_progress_ = false; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetInProgressRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // bool in_progress = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 8)) { + in_progress_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* SetInProgressRequest::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetInProgressRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool in_progress = 1; + if (this->_internal_in_progress() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(1, this->_internal_in_progress(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SetInProgressRequest) + return target; +} + +size_t SetInProgressRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetInProgressRequest) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // bool in_progress = 1; + if (this->_internal_in_progress() != 0) { + total_size += 1 + 1; + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetInProgressRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SetInProgressRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetInProgressRequest::GetClassData() const { return &_class_data_; } + +void SetInProgressRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SetInProgressRequest::MergeFrom(const SetInProgressRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SetInProgressRequest) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_in_progress() != 0) { + _internal_set_in_progress(from._internal_in_progress()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetInProgressRequest::CopyFrom(const SetInProgressRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetInProgressRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetInProgressRequest::IsInitialized() const { + return true; +} + +void SetInProgressRequest::InternalSwap(SetInProgressRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(in_progress_, other->in_progress_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetInProgressRequest::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[2]); +} + +// =================================================================== + +class SetInProgressResponse::_Internal { + public: + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const SetInProgressResponse* msg); +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +SetInProgressResponse::_Internal::camera_server_result(const SetInProgressResponse* msg) { + return *msg->camera_server_result_; +} +SetInProgressResponse::SetInProgressResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetInProgressResponse) +} +SetInProgressResponse::SetInProgressResponse(const SetInProgressResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_camera_server_result()) { + camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from.camera_server_result_); + } else { + camera_server_result_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetInProgressResponse) +} + +inline void SetInProgressResponse::SharedCtor() { +camera_server_result_ = nullptr; +} + +SetInProgressResponse::~SetInProgressResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetInProgressResponse) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void SetInProgressResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete camera_server_result_; +} + +void SetInProgressResponse::ArenaDtor(void* object) { + SetInProgressResponse* _this = reinterpret_cast< SetInProgressResponse* >(object); + (void)_this; +} +void SetInProgressResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void SetInProgressResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SetInProgressResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetInProgressResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { + delete camera_server_result_; + } + camera_server_result_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetInProgressResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* SetInProgressResponse::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetInProgressResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (this->_internal_has_camera_server_result()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::camera_server_result(this), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SetInProgressResponse) + return target; +} + +size_t SetInProgressResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetInProgressResponse) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 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; + if (this->_internal_has_camera_server_result()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *camera_server_result_); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetInProgressResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SetInProgressResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetInProgressResponse::GetClassData() const { return &_class_data_; } + +void SetInProgressResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SetInProgressResponse::MergeFrom(const SetInProgressResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SetInProgressResponse) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_camera_server_result()) { + _internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom(from._internal_camera_server_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetInProgressResponse::CopyFrom(const SetInProgressResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetInProgressResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetInProgressResponse::IsInitialized() const { + return true; +} + +void SetInProgressResponse::InternalSwap(SetInProgressResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(camera_server_result_, other->camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetInProgressResponse::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[3]); +} + +// =================================================================== + +class SubscribeTakePhotoRequest::_Internal { + public: +}; + +SubscribeTakePhotoRequest::SubscribeTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) +} +SubscribeTakePhotoRequest::SubscribeTakePhotoRequest(const SubscribeTakePhotoRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) +} + +inline void SubscribeTakePhotoRequest::SharedCtor() { +} + +SubscribeTakePhotoRequest::~SubscribeTakePhotoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void SubscribeTakePhotoRequest::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); +} + +void SubscribeTakePhotoRequest::ArenaDtor(void* object) { + SubscribeTakePhotoRequest* _this = reinterpret_cast< SubscribeTakePhotoRequest* >(object); + (void)_this; +} +void SubscribeTakePhotoRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void SubscribeTakePhotoRequest::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SubscribeTakePhotoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SubscribeTakePhotoRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* SubscribeTakePhotoRequest::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + return target; +} + +size_t SubscribeTakePhotoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeTakePhotoRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SubscribeTakePhotoRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeTakePhotoRequest::GetClassData() const { return &_class_data_; } + +void SubscribeTakePhotoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SubscribeTakePhotoRequest::MergeFrom(const SubscribeTakePhotoRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SubscribeTakePhotoRequest::CopyFrom(const SubscribeTakePhotoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SubscribeTakePhotoRequest::IsInitialized() const { + return true; +} + +void SubscribeTakePhotoRequest::InternalSwap(SubscribeTakePhotoRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeTakePhotoRequest::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[4]); +} + +// =================================================================== + +class TakePhotoResponse::_Internal { + public: + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const TakePhotoResponse* msg); +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +TakePhotoResponse::_Internal::camera_server_result(const TakePhotoResponse* msg) { + return *msg->camera_server_result_; +} +TakePhotoResponse::TakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.TakePhotoResponse) +} +TakePhotoResponse::TakePhotoResponse(const TakePhotoResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_camera_server_result()) { + camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from.camera_server_result_); + } else { + camera_server_result_ = nullptr; + } + index_ = from.index_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.TakePhotoResponse) +} + +inline void TakePhotoResponse::SharedCtor() { +::memset(reinterpret_cast(this) + static_cast( + reinterpret_cast(&camera_server_result_) - reinterpret_cast(this)), + 0, static_cast(reinterpret_cast(&index_) - + reinterpret_cast(&camera_server_result_)) + sizeof(index_)); +} + +TakePhotoResponse::~TakePhotoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.TakePhotoResponse) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void TakePhotoResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete camera_server_result_; +} + +void TakePhotoResponse::ArenaDtor(void* object) { + TakePhotoResponse* _this = reinterpret_cast< TakePhotoResponse* >(object); + (void)_this; +} +void TakePhotoResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void TakePhotoResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void TakePhotoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.TakePhotoResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { + delete camera_server_result_; + } + camera_server_result_ = nullptr; + index_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* TakePhotoResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // int32 index = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 16)) { + index_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* TakePhotoResponse::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.TakePhotoResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (this->_internal_has_camera_server_result()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::camera_server_result(this), target, stream); + } + + // int32 index = 2; + if (this->_internal_index() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(2, this->_internal_index(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.TakePhotoResponse) + return target; +} + +size_t TakePhotoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.TakePhotoResponse) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 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; + if (this->_internal_has_camera_server_result()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *camera_server_result_); + } + + // int32 index = 2; + if (this->_internal_index() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size( + this->_internal_index()); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData TakePhotoResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + TakePhotoResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*TakePhotoResponse::GetClassData() const { return &_class_data_; } + +void TakePhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void TakePhotoResponse::MergeFrom(const TakePhotoResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.TakePhotoResponse) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_camera_server_result()) { + _internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom(from._internal_camera_server_result()); + } + if (from._internal_index() != 0) { + _internal_set_index(from._internal_index()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void TakePhotoResponse::CopyFrom(const TakePhotoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.TakePhotoResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool TakePhotoResponse::IsInitialized() const { + return true; +} + +void TakePhotoResponse::InternalSwap(TakePhotoResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(TakePhotoResponse, index_) + + sizeof(TakePhotoResponse::index_) + - PROTOBUF_FIELD_OFFSET(TakePhotoResponse, camera_server_result_)>( + reinterpret_cast(&camera_server_result_), + reinterpret_cast(&other->camera_server_result_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata TakePhotoResponse::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[5]); +} + +// =================================================================== + +class PublishPhotoRequest::_Internal { + public: + static const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info(const PublishPhotoRequest* msg); +}; + +const ::mavsdk::rpc::camera_server::CaptureInfo& +PublishPhotoRequest::_Internal::capture_info(const PublishPhotoRequest* msg) { + return *msg->capture_info_; +} +PublishPhotoRequest::PublishPhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.PublishPhotoRequest) +} +PublishPhotoRequest::PublishPhotoRequest(const PublishPhotoRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_capture_info()) { + capture_info_ = new ::mavsdk::rpc::camera_server::CaptureInfo(*from.capture_info_); + } else { + capture_info_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.PublishPhotoRequest) +} + +inline void PublishPhotoRequest::SharedCtor() { +capture_info_ = nullptr; +} + +PublishPhotoRequest::~PublishPhotoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.PublishPhotoRequest) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void PublishPhotoRequest::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete capture_info_; +} + +void PublishPhotoRequest::ArenaDtor(void* object) { + PublishPhotoRequest* _this = reinterpret_cast< PublishPhotoRequest* >(object); + (void)_this; +} +void PublishPhotoRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void PublishPhotoRequest::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void PublishPhotoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.PublishPhotoRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && capture_info_ != nullptr) { + delete capture_info_; + } + capture_info_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* PublishPhotoRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_capture_info(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* PublishPhotoRequest::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.PublishPhotoRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 1; + if (this->_internal_has_capture_info()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::capture_info(this), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.PublishPhotoRequest) + return target; +} + +size_t PublishPhotoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.PublishPhotoRequest) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 1; + if (this->_internal_has_capture_info()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *capture_info_); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData PublishPhotoRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + PublishPhotoRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*PublishPhotoRequest::GetClassData() const { return &_class_data_; } + +void PublishPhotoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void PublishPhotoRequest::MergeFrom(const PublishPhotoRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.PublishPhotoRequest) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_capture_info()) { + _internal_mutable_capture_info()->::mavsdk::rpc::camera_server::CaptureInfo::MergeFrom(from._internal_capture_info()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void PublishPhotoRequest::CopyFrom(const PublishPhotoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.PublishPhotoRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PublishPhotoRequest::IsInitialized() const { + return true; +} + +void PublishPhotoRequest::InternalSwap(PublishPhotoRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(capture_info_, other->capture_info_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata PublishPhotoRequest::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[6]); +} + +// =================================================================== + +class PublishPhotoResponse::_Internal { + public: + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const PublishPhotoResponse* msg); +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +PublishPhotoResponse::_Internal::camera_server_result(const PublishPhotoResponse* msg) { + return *msg->camera_server_result_; +} +PublishPhotoResponse::PublishPhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.PublishPhotoResponse) +} +PublishPhotoResponse::PublishPhotoResponse(const PublishPhotoResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_camera_server_result()) { + camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from.camera_server_result_); + } else { + camera_server_result_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.PublishPhotoResponse) +} + +inline void PublishPhotoResponse::SharedCtor() { +camera_server_result_ = nullptr; +} + +PublishPhotoResponse::~PublishPhotoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.PublishPhotoResponse) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void PublishPhotoResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete camera_server_result_; +} + +void PublishPhotoResponse::ArenaDtor(void* object) { + PublishPhotoResponse* _this = reinterpret_cast< PublishPhotoResponse* >(object); + (void)_this; +} +void PublishPhotoResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void PublishPhotoResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void PublishPhotoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.PublishPhotoResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { + delete camera_server_result_; + } + camera_server_result_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* PublishPhotoResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* PublishPhotoResponse::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.PublishPhotoResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (this->_internal_has_camera_server_result()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::camera_server_result(this), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.PublishPhotoResponse) + return target; +} + +size_t PublishPhotoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.PublishPhotoResponse) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 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; + if (this->_internal_has_camera_server_result()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *camera_server_result_); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData PublishPhotoResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + PublishPhotoResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*PublishPhotoResponse::GetClassData() const { return &_class_data_; } + +void PublishPhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void PublishPhotoResponse::MergeFrom(const PublishPhotoResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.PublishPhotoResponse) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_camera_server_result()) { + _internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom(from._internal_camera_server_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void PublishPhotoResponse::CopyFrom(const PublishPhotoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.PublishPhotoResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PublishPhotoResponse::IsInitialized() const { + return true; +} + +void PublishPhotoResponse::InternalSwap(PublishPhotoResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(camera_server_result_, other->camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata PublishPhotoResponse::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[7]); +} + +// =================================================================== + +class Information::_Internal { + public: +}; + +Information::Information(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Information) +} +Information::Information(const Information& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + vendor_name_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_vendor_name().empty()) { + vendor_name_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_vendor_name(), + GetArenaForAllocation()); + } + model_name_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_model_name().empty()) { + model_name_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_model_name(), + GetArenaForAllocation()); + } + ::memcpy(&focal_length_mm_, &from.focal_length_mm_, + static_cast(reinterpret_cast(&vertical_resolution_px_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Information) +} + +inline void Information::SharedCtor() { +vendor_name_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +model_name_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +::memset(reinterpret_cast(this) + static_cast( + reinterpret_cast(&focal_length_mm_) - reinterpret_cast(this)), + 0, static_cast(reinterpret_cast(&vertical_resolution_px_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); +} + +Information::~Information() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Information) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void Information::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + vendor_name_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + model_name_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +} + +void Information::ArenaDtor(void* object) { + Information* _this = reinterpret_cast< Information* >(object); + (void)_this; +} +void Information::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void Information::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void Information::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Information) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + vendor_name_.ClearToEmpty(); + model_name_.ClearToEmpty(); + ::memset(&focal_length_mm_, 0, static_cast( + reinterpret_cast(&vertical_resolution_px_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* Information::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // string vendor_name = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + auto str = _internal_mutable_vendor_name(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.vendor_name")); + CHK_(ptr); + } else goto handle_unusual; + continue; + // string model_name = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18)) { + auto str = _internal_mutable_model_name(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.model_name")); + CHK_(ptr); + } else goto handle_unusual; + continue; + // float focal_length_mm = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 29)) { + focal_length_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + // float horizontal_sensor_size_mm = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 37)) { + horizontal_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + // float vertical_sensor_size_mm = 5; + case 5: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 45)) { + vertical_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + // uint32 horizontal_resolution_px = 6; + case 6: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 48)) { + horizontal_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // uint32 vertical_resolution_px = 7; + case 7: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 56)) { + vertical_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* Information::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Information) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string vendor_name = 1; + if (!this->_internal_vendor_name().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_vendor_name().data(), static_cast(this->_internal_vendor_name().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.camera_server.Information.vendor_name"); + target = stream->WriteStringMaybeAliased( + 1, this->_internal_vendor_name(), target); + } + + // string model_name = 2; + if (!this->_internal_model_name().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_model_name().data(), static_cast(this->_internal_model_name().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.camera_server.Information.model_name"); + target = stream->WriteStringMaybeAliased( + 2, this->_internal_model_name(), target); + } + + // float focal_length_mm = 3; + if (!(this->_internal_focal_length_mm() <= 0 && this->_internal_focal_length_mm() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(3, this->_internal_focal_length_mm(), target); + } + + // float horizontal_sensor_size_mm = 4; + if (!(this->_internal_horizontal_sensor_size_mm() <= 0 && this->_internal_horizontal_sensor_size_mm() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(4, this->_internal_horizontal_sensor_size_mm(), target); + } + + // float vertical_sensor_size_mm = 5; + if (!(this->_internal_vertical_sensor_size_mm() <= 0 && this->_internal_vertical_sensor_size_mm() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(5, this->_internal_vertical_sensor_size_mm(), target); + } + + // uint32 horizontal_resolution_px = 6; + if (this->_internal_horizontal_resolution_px() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(6, this->_internal_horizontal_resolution_px(), target); + } + + // uint32 vertical_resolution_px = 7; + if (this->_internal_vertical_resolution_px() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(7, this->_internal_vertical_resolution_px(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.Information) + return target; +} + +size_t Information::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Information) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string vendor_name = 1; + if (!this->_internal_vendor_name().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_vendor_name()); + } + + // string model_name = 2; + if (!this->_internal_model_name().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_model_name()); + } + + // float focal_length_mm = 3; + if (!(this->_internal_focal_length_mm() <= 0 && this->_internal_focal_length_mm() >= 0)) { + total_size += 1 + 4; + } + + // float horizontal_sensor_size_mm = 4; + if (!(this->_internal_horizontal_sensor_size_mm() <= 0 && this->_internal_horizontal_sensor_size_mm() >= 0)) { + total_size += 1 + 4; + } + + // float vertical_sensor_size_mm = 5; + if (!(this->_internal_vertical_sensor_size_mm() <= 0 && this->_internal_vertical_sensor_size_mm() >= 0)) { + total_size += 1 + 4; + } + + // uint32 horizontal_resolution_px = 6; + if (this->_internal_horizontal_resolution_px() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( + this->_internal_horizontal_resolution_px()); + } + + // uint32 vertical_resolution_px = 7; + if (this->_internal_vertical_resolution_px() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( + this->_internal_vertical_resolution_px()); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Information::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + Information::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Information::GetClassData() const { return &_class_data_; } + +void Information::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void Information::MergeFrom(const Information& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.Information) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_vendor_name().empty()) { + _internal_set_vendor_name(from._internal_vendor_name()); + } + if (!from._internal_model_name().empty()) { + _internal_set_model_name(from._internal_model_name()); + } + if (!(from._internal_focal_length_mm() <= 0 && from._internal_focal_length_mm() >= 0)) { + _internal_set_focal_length_mm(from._internal_focal_length_mm()); + } + if (!(from._internal_horizontal_sensor_size_mm() <= 0 && from._internal_horizontal_sensor_size_mm() >= 0)) { + _internal_set_horizontal_sensor_size_mm(from._internal_horizontal_sensor_size_mm()); + } + if (!(from._internal_vertical_sensor_size_mm() <= 0 && from._internal_vertical_sensor_size_mm() >= 0)) { + _internal_set_vertical_sensor_size_mm(from._internal_vertical_sensor_size_mm()); + } + if (from._internal_horizontal_resolution_px() != 0) { + _internal_set_horizontal_resolution_px(from._internal_horizontal_resolution_px()); + } + if (from._internal_vertical_resolution_px() != 0) { + _internal_set_vertical_resolution_px(from._internal_vertical_resolution_px()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void Information::CopyFrom(const Information& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Information) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Information::IsInitialized() const { + return true; +} + +void Information::InternalSwap(Information* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &vendor_name_, GetArenaForAllocation(), + &other->vendor_name_, other->GetArenaForAllocation() + ); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &model_name_, GetArenaForAllocation(), + &other->model_name_, other->GetArenaForAllocation() + ); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(Information, vertical_resolution_px_) + + sizeof(Information::vertical_resolution_px_) + - PROTOBUF_FIELD_OFFSET(Information, focal_length_mm_)>( + reinterpret_cast(&focal_length_mm_), + reinterpret_cast(&other->focal_length_mm_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[8]); +} + +// =================================================================== + +class Position::_Internal { + public: +}; + +Position::Position(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Position) +} +Position::Position(const Position& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + ::memcpy(&latitude_deg_, &from.latitude_deg_, + static_cast(reinterpret_cast(&relative_altitude_m_) - + reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Position) +} + +inline void Position::SharedCtor() { +::memset(reinterpret_cast(this) + static_cast( + reinterpret_cast(&latitude_deg_) - reinterpret_cast(this)), + 0, static_cast(reinterpret_cast(&relative_altitude_m_) - + reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); +} + +Position::~Position() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Position) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void Position::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); +} + +void Position::ArenaDtor(void* object) { + Position* _this = reinterpret_cast< Position* >(object); + (void)_this; +} +void Position::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void Position::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void Position::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Position) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&latitude_deg_, 0, static_cast( + reinterpret_cast(&relative_altitude_m_) - + reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* Position::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // double latitude_deg = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 9)) { + latitude_deg_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(double); + } else goto handle_unusual; + continue; + // double longitude_deg = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 17)) { + longitude_deg_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(double); + } else goto handle_unusual; + continue; + // float absolute_altitude_m = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 29)) { + absolute_altitude_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + // float relative_altitude_m = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 37)) { + relative_altitude_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* Position::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Position) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double latitude_deg = 1; + if (!(this->_internal_latitude_deg() <= 0 && this->_internal_latitude_deg() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteDoubleToArray(1, this->_internal_latitude_deg(), target); + } + + // double longitude_deg = 2; + if (!(this->_internal_longitude_deg() <= 0 && this->_internal_longitude_deg() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteDoubleToArray(2, this->_internal_longitude_deg(), target); + } + + // float absolute_altitude_m = 3; + if (!(this->_internal_absolute_altitude_m() <= 0 && this->_internal_absolute_altitude_m() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(3, this->_internal_absolute_altitude_m(), target); + } + + // float relative_altitude_m = 4; + if (!(this->_internal_relative_altitude_m() <= 0 && this->_internal_relative_altitude_m() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(4, this->_internal_relative_altitude_m(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.Position) + return target; +} + +size_t Position::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Position) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // double latitude_deg = 1; + if (!(this->_internal_latitude_deg() <= 0 && this->_internal_latitude_deg() >= 0)) { + total_size += 1 + 8; + } + + // double longitude_deg = 2; + if (!(this->_internal_longitude_deg() <= 0 && this->_internal_longitude_deg() >= 0)) { + total_size += 1 + 8; + } + + // float absolute_altitude_m = 3; + if (!(this->_internal_absolute_altitude_m() <= 0 && this->_internal_absolute_altitude_m() >= 0)) { + total_size += 1 + 4; + } + + // float relative_altitude_m = 4; + if (!(this->_internal_relative_altitude_m() <= 0 && this->_internal_relative_altitude_m() >= 0)) { + total_size += 1 + 4; + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Position::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + Position::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Position::GetClassData() const { return &_class_data_; } + +void Position::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void Position::MergeFrom(const Position& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.Position) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!(from._internal_latitude_deg() <= 0 && from._internal_latitude_deg() >= 0)) { + _internal_set_latitude_deg(from._internal_latitude_deg()); + } + if (!(from._internal_longitude_deg() <= 0 && from._internal_longitude_deg() >= 0)) { + _internal_set_longitude_deg(from._internal_longitude_deg()); + } + if (!(from._internal_absolute_altitude_m() <= 0 && from._internal_absolute_altitude_m() >= 0)) { + _internal_set_absolute_altitude_m(from._internal_absolute_altitude_m()); + } + if (!(from._internal_relative_altitude_m() <= 0 && from._internal_relative_altitude_m() >= 0)) { + _internal_set_relative_altitude_m(from._internal_relative_altitude_m()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void Position::CopyFrom(const Position& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Position) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Position::IsInitialized() const { + return true; +} + +void Position::InternalSwap(Position* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(Position, relative_altitude_m_) + + sizeof(Position::relative_altitude_m_) + - PROTOBUF_FIELD_OFFSET(Position, latitude_deg_)>( + reinterpret_cast(&latitude_deg_), + reinterpret_cast(&other->latitude_deg_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[9]); +} + +// =================================================================== + +class Quaternion::_Internal { + public: +}; + +Quaternion::Quaternion(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Quaternion) +} +Quaternion::Quaternion(const Quaternion& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + ::memcpy(&w_, &from.w_, + static_cast(reinterpret_cast(&z_) - + reinterpret_cast(&w_)) + sizeof(z_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Quaternion) +} + +inline void Quaternion::SharedCtor() { +::memset(reinterpret_cast(this) + static_cast( + reinterpret_cast(&w_) - reinterpret_cast(this)), + 0, static_cast(reinterpret_cast(&z_) - + reinterpret_cast(&w_)) + sizeof(z_)); +} + +Quaternion::~Quaternion() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Quaternion) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void Quaternion::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); +} + +void Quaternion::ArenaDtor(void* object) { + Quaternion* _this = reinterpret_cast< Quaternion* >(object); + (void)_this; +} +void Quaternion::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void Quaternion::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void Quaternion::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Quaternion) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&w_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&w_)) + sizeof(z_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* Quaternion::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // float w = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 13)) { + w_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + // float x = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 21)) { + x_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + // float y = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 29)) { + y_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + // float z = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 37)) { + z_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* Quaternion::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Quaternion) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float w = 1; + if (!(this->_internal_w() <= 0 && this->_internal_w() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_w(), target); + } + + // float x = 2; + if (!(this->_internal_x() <= 0 && this->_internal_x() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(2, this->_internal_x(), target); + } + + // float y = 3; + if (!(this->_internal_y() <= 0 && this->_internal_y() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(3, this->_internal_y(), target); + } + + // float z = 4; + if (!(this->_internal_z() <= 0 && this->_internal_z() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(4, this->_internal_z(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.Quaternion) + return target; +} + +size_t Quaternion::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Quaternion) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float w = 1; + if (!(this->_internal_w() <= 0 && this->_internal_w() >= 0)) { + total_size += 1 + 4; + } + + // float x = 2; + if (!(this->_internal_x() <= 0 && this->_internal_x() >= 0)) { + total_size += 1 + 4; + } + + // float y = 3; + if (!(this->_internal_y() <= 0 && this->_internal_y() >= 0)) { + total_size += 1 + 4; + } + + // float z = 4; + if (!(this->_internal_z() <= 0 && this->_internal_z() >= 0)) { + total_size += 1 + 4; + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Quaternion::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + Quaternion::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Quaternion::GetClassData() const { return &_class_data_; } + +void Quaternion::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void Quaternion::MergeFrom(const Quaternion& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.Quaternion) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!(from._internal_w() <= 0 && from._internal_w() >= 0)) { + _internal_set_w(from._internal_w()); + } + if (!(from._internal_x() <= 0 && from._internal_x() >= 0)) { + _internal_set_x(from._internal_x()); + } + if (!(from._internal_y() <= 0 && from._internal_y() >= 0)) { + _internal_set_y(from._internal_y()); + } + if (!(from._internal_z() <= 0 && from._internal_z() >= 0)) { + _internal_set_z(from._internal_z()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void Quaternion::CopyFrom(const Quaternion& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Quaternion) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Quaternion::IsInitialized() const { + return true; +} + +void Quaternion::InternalSwap(Quaternion* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(Quaternion, z_) + + sizeof(Quaternion::z_) + - PROTOBUF_FIELD_OFFSET(Quaternion, w_)>( + reinterpret_cast(&w_), + reinterpret_cast(&other->w_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[10]); +} + +// =================================================================== + +class CaptureInfo::_Internal { + public: + static const ::mavsdk::rpc::camera_server::Position& position(const CaptureInfo* msg); + static const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion(const CaptureInfo* msg); +}; + +const ::mavsdk::rpc::camera_server::Position& +CaptureInfo::_Internal::position(const CaptureInfo* msg) { + return *msg->position_; +} +const ::mavsdk::rpc::camera_server::Quaternion& +CaptureInfo::_Internal::attitude_quaternion(const CaptureInfo* msg) { + return *msg->attitude_quaternion_; +} +CaptureInfo::CaptureInfo(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CaptureInfo) +} +CaptureInfo::CaptureInfo(const CaptureInfo& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + file_url_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_file_url().empty()) { + file_url_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_file_url(), + GetArenaForAllocation()); + } + if (from._internal_has_position()) { + position_ = new ::mavsdk::rpc::camera_server::Position(*from.position_); + } else { + position_ = nullptr; + } + if (from._internal_has_attitude_quaternion()) { + attitude_quaternion_ = new ::mavsdk::rpc::camera_server::Quaternion(*from.attitude_quaternion_); + } else { + attitude_quaternion_ = nullptr; + } + ::memcpy(&time_utc_us_, &from.time_utc_us_, + static_cast(reinterpret_cast(&index_) - + reinterpret_cast(&time_utc_us_)) + sizeof(index_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CaptureInfo) +} + +inline void CaptureInfo::SharedCtor() { +file_url_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +::memset(reinterpret_cast(this) + static_cast( + reinterpret_cast(&position_) - reinterpret_cast(this)), + 0, static_cast(reinterpret_cast(&index_) - + reinterpret_cast(&position_)) + sizeof(index_)); +} + +CaptureInfo::~CaptureInfo() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CaptureInfo) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void CaptureInfo::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + file_url_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete position_; + if (this != internal_default_instance()) delete attitude_quaternion_; +} + +void CaptureInfo::ArenaDtor(void* object) { + CaptureInfo* _this = reinterpret_cast< CaptureInfo* >(object); + (void)_this; +} +void CaptureInfo::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void CaptureInfo::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void CaptureInfo::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CaptureInfo) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + file_url_.ClearToEmpty(); + if (GetArenaForAllocation() == nullptr && position_ != nullptr) { + delete position_; + } + position_ = nullptr; + if (GetArenaForAllocation() == nullptr && attitude_quaternion_ != nullptr) { + delete attitude_quaternion_; + } + attitude_quaternion_ = nullptr; + ::memset(&time_utc_us_, 0, static_cast( + reinterpret_cast(&index_) - + reinterpret_cast(&time_utc_us_)) + sizeof(index_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* CaptureInfo::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.Position position = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_position(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18)) { + ptr = ctx->ParseMessage(_internal_mutable_attitude_quaternion(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // uint64 time_utc_us = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 24)) { + time_utc_us_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // bool is_success = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 32)) { + is_success_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // int32 index = 5; + case 5: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 40)) { + index_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // string file_url = 6; + case 6: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 50)) { + auto str = _internal_mutable_file_url(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.camera_server.CaptureInfo.file_url")); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* CaptureInfo::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CaptureInfo) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.Position position = 1; + if (this->_internal_has_position()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::position(this), target, stream); + } + + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + if (this->_internal_has_attitude_quaternion()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 2, _Internal::attitude_quaternion(this), target, stream); + } + + // uint64 time_utc_us = 3; + if (this->_internal_time_utc_us() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt64ToArray(3, this->_internal_time_utc_us(), target); + } + + // bool is_success = 4; + if (this->_internal_is_success() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(4, this->_internal_is_success(), target); + } + + // int32 index = 5; + if (this->_internal_index() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(5, this->_internal_index(), target); + } + + // string file_url = 6; + if (!this->_internal_file_url().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_file_url().data(), static_cast(this->_internal_file_url().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.camera_server.CaptureInfo.file_url"); + target = stream->WriteStringMaybeAliased( + 6, this->_internal_file_url(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.CaptureInfo) + return target; +} + +size_t CaptureInfo::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CaptureInfo) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string file_url = 6; + if (!this->_internal_file_url().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_file_url()); + } + + // .mavsdk.rpc.camera_server.Position position = 1; + if (this->_internal_has_position()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *position_); + } + + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + if (this->_internal_has_attitude_quaternion()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *attitude_quaternion_); + } + + // uint64 time_utc_us = 3; + if (this->_internal_time_utc_us() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt64Size( + this->_internal_time_utc_us()); + } + + // bool is_success = 4; + if (this->_internal_is_success() != 0) { + total_size += 1 + 1; + } + + // int32 index = 5; + if (this->_internal_index() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size( + this->_internal_index()); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CaptureInfo::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + CaptureInfo::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CaptureInfo::GetClassData() const { return &_class_data_; } + +void CaptureInfo::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void CaptureInfo::MergeFrom(const CaptureInfo& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.CaptureInfo) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_file_url().empty()) { + _internal_set_file_url(from._internal_file_url()); + } + if (from._internal_has_position()) { + _internal_mutable_position()->::mavsdk::rpc::camera_server::Position::MergeFrom(from._internal_position()); + } + if (from._internal_has_attitude_quaternion()) { + _internal_mutable_attitude_quaternion()->::mavsdk::rpc::camera_server::Quaternion::MergeFrom(from._internal_attitude_quaternion()); + } + if (from._internal_time_utc_us() != 0) { + _internal_set_time_utc_us(from._internal_time_utc_us()); + } + if (from._internal_is_success() != 0) { + _internal_set_is_success(from._internal_is_success()); + } + if (from._internal_index() != 0) { + _internal_set_index(from._internal_index()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void CaptureInfo::CopyFrom(const CaptureInfo& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CaptureInfo) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CaptureInfo::IsInitialized() const { + return true; +} + +void CaptureInfo::InternalSwap(CaptureInfo* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &file_url_, GetArenaForAllocation(), + &other->file_url_, other->GetArenaForAllocation() + ); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(CaptureInfo, index_) + + sizeof(CaptureInfo::index_) + - PROTOBUF_FIELD_OFFSET(CaptureInfo, position_)>( + reinterpret_cast(&position_), + reinterpret_cast(&other->position_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[11]); +} + +// =================================================================== + +class CameraServerResult::_Internal { + public: +}; + +CameraServerResult::CameraServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CameraServerResult) +} +CameraServerResult::CameraServerResult(const CameraServerResult& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + result_str_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_result_str().empty()) { + result_str_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_result_str(), + GetArenaForAllocation()); + } + result_ = from.result_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CameraServerResult) +} + +inline void CameraServerResult::SharedCtor() { +result_str_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +result_ = 0; +} + +CameraServerResult::~CameraServerResult() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CameraServerResult) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void CameraServerResult::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + result_str_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +} + +void CameraServerResult::ArenaDtor(void* object) { + CameraServerResult* _this = reinterpret_cast< CameraServerResult* >(object); + (void)_this; +} +void CameraServerResult::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void CameraServerResult::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void CameraServerResult::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CameraServerResult) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + result_str_.ClearToEmpty(); + result_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* CameraServerResult::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 8)) { + ::PROTOBUF_NAMESPACE_ID::uint64 val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + _internal_set_result(static_cast<::mavsdk::rpc::camera_server::CameraServerResult_Result>(val)); + } else goto handle_unusual; + continue; + // string result_str = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18)) { + auto str = _internal_mutable_result_str(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.camera_server.CameraServerResult.result_str")); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* CameraServerResult::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CameraServerResult) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; + if (this->_internal_result() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteEnumToArray( + 1, this->_internal_result(), target); + } + + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_result_str().data(), static_cast(this->_internal_result_str().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.camera_server.CameraServerResult.result_str"); + target = stream->WriteStringMaybeAliased( + 2, this->_internal_result_str(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.CameraServerResult) + return target; +} + +size_t CameraServerResult::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CameraServerResult) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_result_str()); + } + + // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; + if (this->_internal_result() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::EnumSize(this->_internal_result()); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CameraServerResult::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + CameraServerResult::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CameraServerResult::GetClassData() const { return &_class_data_; } + +void CameraServerResult::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void CameraServerResult::MergeFrom(const CameraServerResult& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.CameraServerResult) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_result_str().empty()) { + _internal_set_result_str(from._internal_result_str()); + } + if (from._internal_result() != 0) { + _internal_set_result(from._internal_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void CameraServerResult::CopyFrom(const CameraServerResult& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CameraServerResult) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CameraServerResult::IsInitialized() const { + return true; +} + +void CameraServerResult::InternalSwap(CameraServerResult* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &result_str_, GetArenaForAllocation(), + &other->result_str_, other->GetArenaForAllocation() + ); + swap(result_, other->result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::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[12]); +} + +// @@protoc_insertion_point(namespace_scope) +} // namespace camera_server +} // namespace rpc +} // namespace mavsdk +PROTOBUF_NAMESPACE_OPEN +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetInformationRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetInformationRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetInformationRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetInformationResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetInformationResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetInformationResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetInProgressRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetInProgressRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetInProgressRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetInProgressResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetInProgressResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetInProgressResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::TakePhotoResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::TakePhotoResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::PublishPhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::PublishPhotoRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::PublishPhotoRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::PublishPhotoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::PublishPhotoResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::PublishPhotoResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::Information* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::Information >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::Information >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::Position* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::Position >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::Position >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::Quaternion* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::Quaternion >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::Quaternion >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::CaptureInfo* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::CaptureInfo >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::CaptureInfo >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::CameraServerResult* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::CameraServerResult >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::CameraServerResult >(arena); +} +PROTOBUF_NAMESPACE_CLOSE + +// @@protoc_insertion_point(global_scope) +#include 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 new file mode 100644 index 0000000000..a6342988e1 --- /dev/null +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -0,0 +1,3683 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: camera_server/camera_server.proto + +#ifndef GOOGLE_PROTOBUF_INCLUDED_camera_5fserver_2fcamera_5fserver_2eproto +#define GOOGLE_PROTOBUF_INCLUDED_camera_5fserver_2fcamera_5fserver_2eproto + +#include +#include + +#include +#if PROTOBUF_VERSION < 3017000 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3017003 < PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "mavsdk_options.pb.h" +// @@protoc_insertion_point(includes) +#include +#define PROTOBUF_INTERNAL_EXPORT_camera_5fserver_2fcamera_5fserver_2eproto +PROTOBUF_NAMESPACE_OPEN +namespace internal { +class AnyMetadata; +} // namespace internal +PROTOBUF_NAMESPACE_CLOSE + +// Internal implementation detail -- do not use these members. +struct TableStruct_camera_5fserver_2fcamera_5fserver_2eproto { + static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTableField entries[] + PROTOBUF_SECTION_VARIABLE(protodesc_cold); + static const ::PROTOBUF_NAMESPACE_ID::internal::AuxiliaryParseTableField aux[] + PROTOBUF_SECTION_VARIABLE(protodesc_cold); + static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[13] + PROTOBUF_SECTION_VARIABLE(protodesc_cold); + static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[]; + static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[]; + static const ::PROTOBUF_NAMESPACE_ID::uint32 offsets[]; +}; +extern const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto; +namespace mavsdk { +namespace rpc { +namespace camera_server { +class CameraServerResult; +struct CameraServerResultDefaultTypeInternal; +extern CameraServerResultDefaultTypeInternal _CameraServerResult_default_instance_; +class CaptureInfo; +struct CaptureInfoDefaultTypeInternal; +extern CaptureInfoDefaultTypeInternal _CaptureInfo_default_instance_; +class Information; +struct InformationDefaultTypeInternal; +extern InformationDefaultTypeInternal _Information_default_instance_; +class Position; +struct PositionDefaultTypeInternal; +extern PositionDefaultTypeInternal _Position_default_instance_; +class PublishPhotoRequest; +struct PublishPhotoRequestDefaultTypeInternal; +extern PublishPhotoRequestDefaultTypeInternal _PublishPhotoRequest_default_instance_; +class PublishPhotoResponse; +struct PublishPhotoResponseDefaultTypeInternal; +extern PublishPhotoResponseDefaultTypeInternal _PublishPhotoResponse_default_instance_; +class Quaternion; +struct QuaternionDefaultTypeInternal; +extern QuaternionDefaultTypeInternal _Quaternion_default_instance_; +class SetInProgressRequest; +struct SetInProgressRequestDefaultTypeInternal; +extern SetInProgressRequestDefaultTypeInternal _SetInProgressRequest_default_instance_; +class SetInProgressResponse; +struct SetInProgressResponseDefaultTypeInternal; +extern SetInProgressResponseDefaultTypeInternal _SetInProgressResponse_default_instance_; +class SetInformationRequest; +struct SetInformationRequestDefaultTypeInternal; +extern SetInformationRequestDefaultTypeInternal _SetInformationRequest_default_instance_; +class SetInformationResponse; +struct SetInformationResponseDefaultTypeInternal; +extern SetInformationResponseDefaultTypeInternal _SetInformationResponse_default_instance_; +class SubscribeTakePhotoRequest; +struct SubscribeTakePhotoRequestDefaultTypeInternal; +extern SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_default_instance_; +class TakePhotoResponse; +struct TakePhotoResponseDefaultTypeInternal; +extern TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; +} // namespace camera_server +} // namespace rpc +} // namespace mavsdk +PROTOBUF_NAMESPACE_OPEN +template<> ::mavsdk::rpc::camera_server::CameraServerResult* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(Arena*); +template<> ::mavsdk::rpc::camera_server::CaptureInfo* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(Arena*); +template<> ::mavsdk::rpc::camera_server::Information* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(Arena*); +template<> ::mavsdk::rpc::camera_server::Position* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Position>(Arena*); +template<> ::mavsdk::rpc::camera_server::PublishPhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::PublishPhotoRequest>(Arena*); +template<> ::mavsdk::rpc::camera_server::PublishPhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::PublishPhotoResponse>(Arena*); +template<> ::mavsdk::rpc::camera_server::Quaternion* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Quaternion>(Arena*); +template<> ::mavsdk::rpc::camera_server::SetInProgressRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInProgressRequest>(Arena*); +template<> ::mavsdk::rpc::camera_server::SetInProgressResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInProgressResponse>(Arena*); +template<> ::mavsdk::rpc::camera_server::SetInformationRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInformationRequest>(Arena*); +template<> ::mavsdk::rpc::camera_server::SetInformationResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInformationResponse>(Arena*); +template<> ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest>(Arena*); +template<> ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::TakePhotoResponse>(Arena*); +PROTOBUF_NAMESPACE_CLOSE +namespace mavsdk { +namespace rpc { +namespace camera_server { + +enum CameraServerResult_Result : int { + CameraServerResult_Result_RESULT_UNKNOWN = 0, + CameraServerResult_Result_RESULT_SUCCESS = 1, + CameraServerResult_Result_RESULT_IN_PROGRESS = 2, + CameraServerResult_Result_RESULT_BUSY = 3, + CameraServerResult_Result_RESULT_DENIED = 4, + CameraServerResult_Result_RESULT_ERROR = 5, + CameraServerResult_Result_RESULT_TIMEOUT = 6, + CameraServerResult_Result_RESULT_WRONG_ARGUMENT = 7, + CameraServerResult_Result_RESULT_NO_SYSTEM = 8, + CameraServerResult_Result_CameraServerResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::PROTOBUF_NAMESPACE_ID::int32>::min(), + CameraServerResult_Result_CameraServerResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::PROTOBUF_NAMESPACE_ID::int32>::max() +}; +bool CameraServerResult_Result_IsValid(int value); +constexpr CameraServerResult_Result CameraServerResult_Result_Result_MIN = CameraServerResult_Result_RESULT_UNKNOWN; +constexpr CameraServerResult_Result CameraServerResult_Result_Result_MAX = CameraServerResult_Result_RESULT_NO_SYSTEM; +constexpr int CameraServerResult_Result_Result_ARRAYSIZE = CameraServerResult_Result_Result_MAX + 1; + +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* CameraServerResult_Result_descriptor(); +template +inline const std::string& CameraServerResult_Result_Name(T enum_t_value) { + static_assert(::std::is_same::value || + ::std::is_integral::value, + "Incorrect type passed to function CameraServerResult_Result_Name."); + return ::PROTOBUF_NAMESPACE_ID::internal::NameOfEnum( + CameraServerResult_Result_descriptor(), enum_t_value); +} +inline bool CameraServerResult_Result_Parse( + ::PROTOBUF_NAMESPACE_ID::ConstStringParam name, CameraServerResult_Result* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + CameraServerResult_Result_descriptor(), name, value); +} +// =================================================================== + +class SetInformationRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInformationRequest) */ { + public: + inline SetInformationRequest() : SetInformationRequest(nullptr) {} + ~SetInformationRequest() override; + explicit constexpr SetInformationRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetInformationRequest(const SetInformationRequest& from); + SetInformationRequest(SetInformationRequest&& from) noexcept + : SetInformationRequest() { + *this = ::std::move(from); + } + + inline SetInformationRequest& operator=(const SetInformationRequest& from) { + CopyFrom(from); + return *this; + } + inline SetInformationRequest& operator=(SetInformationRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetInformationRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_SetInformationRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + friend void swap(SetInformationRequest& a, SetInformationRequest& b) { + a.Swap(&b); + } + inline void Swap(SetInformationRequest* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetInformationRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline SetInformationRequest* New() const final { + return new SetInformationRequest(); + } + + SetInformationRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetInformationRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const SetInformationRequest& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetInformationRequest* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.SetInformationRequest"; + } + protected: + explicit SetInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kInformationFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.Information information = 1; + bool has_information() const; + private: + bool _internal_has_information() const; + public: + void clear_information(); + const ::mavsdk::rpc::camera_server::Information& information() const; + PROTOBUF_MUST_USE_RESULT ::mavsdk::rpc::camera_server::Information* release_information(); + ::mavsdk::rpc::camera_server::Information* mutable_information(); + void set_allocated_information(::mavsdk::rpc::camera_server::Information* information); + private: + const ::mavsdk::rpc::camera_server::Information& _internal_information() const; + ::mavsdk::rpc::camera_server::Information* _internal_mutable_information(); + public: + void unsafe_arena_set_allocated_information( + ::mavsdk::rpc::camera_server::Information* information); + ::mavsdk::rpc::camera_server::Information* unsafe_arena_release_information(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInformationRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::camera_server::Information* information_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class SetInformationResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInformationResponse) */ { + public: + inline SetInformationResponse() : SetInformationResponse(nullptr) {} + ~SetInformationResponse() override; + explicit constexpr SetInformationResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetInformationResponse(const SetInformationResponse& from); + SetInformationResponse(SetInformationResponse&& from) noexcept + : SetInformationResponse() { + *this = ::std::move(from); + } + + inline SetInformationResponse& operator=(const SetInformationResponse& from) { + CopyFrom(from); + return *this; + } + inline SetInformationResponse& operator=(SetInformationResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetInformationResponse& default_instance() { + return *internal_default_instance(); + } + static inline const SetInformationResponse* internal_default_instance() { + return reinterpret_cast( + &_SetInformationResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + friend void swap(SetInformationResponse& a, SetInformationResponse& b) { + a.Swap(&b); + } + inline void Swap(SetInformationResponse* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetInformationResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline SetInformationResponse* New() const final { + return new SetInformationResponse(); + } + + SetInformationResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetInformationResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const SetInformationResponse& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetInformationResponse* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.SetInformationResponse"; + } + protected: + explicit SetInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::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; + private: + bool _internal_has_camera_server_result() const; + public: + void clear_camera_server_result(); + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_MUST_USE_RESULT ::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* 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: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInformationResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class SetInProgressRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInProgressRequest) */ { + public: + inline SetInProgressRequest() : SetInProgressRequest(nullptr) {} + ~SetInProgressRequest() override; + explicit constexpr SetInProgressRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetInProgressRequest(const SetInProgressRequest& from); + SetInProgressRequest(SetInProgressRequest&& from) noexcept + : SetInProgressRequest() { + *this = ::std::move(from); + } + + inline SetInProgressRequest& operator=(const SetInProgressRequest& from) { + CopyFrom(from); + return *this; + } + inline SetInProgressRequest& operator=(SetInProgressRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetInProgressRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetInProgressRequest* internal_default_instance() { + return reinterpret_cast( + &_SetInProgressRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(SetInProgressRequest& a, SetInProgressRequest& b) { + a.Swap(&b); + } + inline void Swap(SetInProgressRequest* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetInProgressRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline SetInProgressRequest* New() const final { + return new SetInProgressRequest(); + } + + SetInProgressRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetInProgressRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const SetInProgressRequest& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetInProgressRequest* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.SetInProgressRequest"; + } + protected: + explicit SetInProgressRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::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) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + bool in_progress_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class SetInProgressResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInProgressResponse) */ { + public: + inline SetInProgressResponse() : SetInProgressResponse(nullptr) {} + ~SetInProgressResponse() override; + explicit constexpr SetInProgressResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetInProgressResponse(const SetInProgressResponse& from); + SetInProgressResponse(SetInProgressResponse&& from) noexcept + : SetInProgressResponse() { + *this = ::std::move(from); + } + + inline SetInProgressResponse& operator=(const SetInProgressResponse& from) { + CopyFrom(from); + return *this; + } + inline SetInProgressResponse& operator=(SetInProgressResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetInProgressResponse& default_instance() { + return *internal_default_instance(); + } + static inline const SetInProgressResponse* internal_default_instance() { + return reinterpret_cast( + &_SetInProgressResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + friend void swap(SetInProgressResponse& a, SetInProgressResponse& b) { + a.Swap(&b); + } + inline void Swap(SetInProgressResponse* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetInProgressResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline SetInProgressResponse* New() const final { + return new SetInProgressResponse(); + } + + SetInProgressResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetInProgressResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const SetInProgressResponse& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetInProgressResponse* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.SetInProgressResponse"; + } + protected: + explicit SetInProgressResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::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; + private: + bool _internal_has_camera_server_result() const; + public: + void clear_camera_server_result(); + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_MUST_USE_RESULT ::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* 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: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetInProgressResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class SubscribeTakePhotoRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) */ { + public: + inline SubscribeTakePhotoRequest() : SubscribeTakePhotoRequest(nullptr) {} + ~SubscribeTakePhotoRequest() override; + explicit constexpr SubscribeTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeTakePhotoRequest(const SubscribeTakePhotoRequest& from); + SubscribeTakePhotoRequest(SubscribeTakePhotoRequest&& from) noexcept + : SubscribeTakePhotoRequest() { + *this = ::std::move(from); + } + + inline SubscribeTakePhotoRequest& operator=(const SubscribeTakePhotoRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeTakePhotoRequest& operator=(SubscribeTakePhotoRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SubscribeTakePhotoRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeTakePhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeTakePhotoRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + friend void swap(SubscribeTakePhotoRequest& a, SubscribeTakePhotoRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeTakePhotoRequest* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeTakePhotoRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline SubscribeTakePhotoRequest* New() const final { + return new SubscribeTakePhotoRequest(); + } + + SubscribeTakePhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SubscribeTakePhotoRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const SubscribeTakePhotoRequest& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SubscribeTakePhotoRequest* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeTakePhotoRequest"; + } + protected: + explicit SubscribeTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeTakePhotoRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class TakePhotoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.TakePhotoResponse) */ { + public: + inline TakePhotoResponse() : TakePhotoResponse(nullptr) {} + ~TakePhotoResponse() override; + explicit constexpr TakePhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + TakePhotoResponse(const TakePhotoResponse& from); + TakePhotoResponse(TakePhotoResponse&& from) noexcept + : TakePhotoResponse() { + *this = ::std::move(from); + } + + inline TakePhotoResponse& operator=(const TakePhotoResponse& from) { + CopyFrom(from); + return *this; + } + inline TakePhotoResponse& operator=(TakePhotoResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const TakePhotoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const TakePhotoResponse* internal_default_instance() { + return reinterpret_cast( + &_TakePhotoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + friend void swap(TakePhotoResponse& a, TakePhotoResponse& b) { + a.Swap(&b); + } + inline void Swap(TakePhotoResponse* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(TakePhotoResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline TakePhotoResponse* New() const final { + return new TakePhotoResponse(); + } + + TakePhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const TakePhotoResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const TakePhotoResponse& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(TakePhotoResponse* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.TakePhotoResponse"; + } + protected: + explicit TakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kCameraServerResultFieldNumber = 1, + kIndexFieldNumber = 2, + }; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + private: + bool _internal_has_camera_server_result() const; + public: + void clear_camera_server_result(); + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_MUST_USE_RESULT ::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* 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: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + + // int32 index = 2; + void clear_index(); + ::PROTOBUF_NAMESPACE_ID::int32 index() const; + void set_index(::PROTOBUF_NAMESPACE_ID::int32 value); + private: + ::PROTOBUF_NAMESPACE_ID::int32 _internal_index() const; + void _internal_set_index(::PROTOBUF_NAMESPACE_ID::int32 value); + public: + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.TakePhotoResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + ::PROTOBUF_NAMESPACE_ID::int32 index_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class PublishPhotoRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.PublishPhotoRequest) */ { + public: + inline PublishPhotoRequest() : PublishPhotoRequest(nullptr) {} + ~PublishPhotoRequest() override; + explicit constexpr PublishPhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + PublishPhotoRequest(const PublishPhotoRequest& from); + PublishPhotoRequest(PublishPhotoRequest&& from) noexcept + : PublishPhotoRequest() { + *this = ::std::move(from); + } + + inline PublishPhotoRequest& operator=(const PublishPhotoRequest& from) { + CopyFrom(from); + return *this; + } + inline PublishPhotoRequest& operator=(PublishPhotoRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const PublishPhotoRequest& default_instance() { + return *internal_default_instance(); + } + static inline const PublishPhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishPhotoRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + friend void swap(PublishPhotoRequest& a, PublishPhotoRequest& b) { + a.Swap(&b); + } + inline void Swap(PublishPhotoRequest* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(PublishPhotoRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline PublishPhotoRequest* New() const final { + return new PublishPhotoRequest(); + } + + PublishPhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const PublishPhotoRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const PublishPhotoRequest& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PublishPhotoRequest* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.PublishPhotoRequest"; + } + protected: + explicit PublishPhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kCaptureInfoFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 1; + bool has_capture_info() const; + private: + bool _internal_has_capture_info() const; + public: + void clear_capture_info(); + const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; + PROTOBUF_MUST_USE_RESULT ::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* capture_info); + private: + const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; + ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); + public: + void unsafe_arena_set_allocated_capture_info( + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info); + ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.PublishPhotoRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class PublishPhotoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.PublishPhotoResponse) */ { + public: + inline PublishPhotoResponse() : PublishPhotoResponse(nullptr) {} + ~PublishPhotoResponse() override; + explicit constexpr PublishPhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + PublishPhotoResponse(const PublishPhotoResponse& from); + PublishPhotoResponse(PublishPhotoResponse&& from) noexcept + : PublishPhotoResponse() { + *this = ::std::move(from); + } + + inline PublishPhotoResponse& operator=(const PublishPhotoResponse& from) { + CopyFrom(from); + return *this; + } + inline PublishPhotoResponse& operator=(PublishPhotoResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const PublishPhotoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const PublishPhotoResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishPhotoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 7; + + friend void swap(PublishPhotoResponse& a, PublishPhotoResponse& b) { + a.Swap(&b); + } + inline void Swap(PublishPhotoResponse* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(PublishPhotoResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline PublishPhotoResponse* New() const final { + return new PublishPhotoResponse(); + } + + PublishPhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const PublishPhotoResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const PublishPhotoResponse& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PublishPhotoResponse* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.PublishPhotoResponse"; + } + protected: + explicit PublishPhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::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; + private: + bool _internal_has_camera_server_result() const; + public: + void clear_camera_server_result(); + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_MUST_USE_RESULT ::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* 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: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.PublishPhotoResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class Information final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { + public: + inline Information() : Information(nullptr) {} + ~Information() override; + explicit constexpr Information(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Information(const Information& from); + Information(Information&& from) noexcept + : Information() { + *this = ::std::move(from); + } + + inline Information& operator=(const Information& from) { + CopyFrom(from); + return *this; + } + inline Information& operator=(Information&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const Information& default_instance() { + return *internal_default_instance(); + } + static inline const Information* internal_default_instance() { + return reinterpret_cast( + &_Information_default_instance_); + } + static constexpr int kIndexInFileMessages = + 8; + + friend void swap(Information& a, Information& b) { + a.Swap(&b); + } + inline void Swap(Information* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Information* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline Information* New() const final { + return new Information(); + } + + Information* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Information& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const Information& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Information* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.Information"; + } + protected: + explicit Information(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kVendorNameFieldNumber = 1, + kModelNameFieldNumber = 2, + kFocalLengthMmFieldNumber = 3, + kHorizontalSensorSizeMmFieldNumber = 4, + kVerticalSensorSizeMmFieldNumber = 5, + kHorizontalResolutionPxFieldNumber = 6, + kVerticalResolutionPxFieldNumber = 7, + }; + // string vendor_name = 1; + void clear_vendor_name(); + const std::string& vendor_name() const; + template + void set_vendor_name(ArgT0&& arg0, ArgT... args); + std::string* mutable_vendor_name(); + PROTOBUF_MUST_USE_RESULT std::string* release_vendor_name(); + void set_allocated_vendor_name(std::string* vendor_name); + 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(ArgT0&& arg0, ArgT... args); + std::string* mutable_model_name(); + PROTOBUF_MUST_USE_RESULT std::string* release_model_name(); + void set_allocated_model_name(std::string* model_name); + 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: + + // float focal_length_mm = 3; + 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 = 4; + 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 = 5; + 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 = 6; + void clear_horizontal_resolution_px(); + ::PROTOBUF_NAMESPACE_ID::uint32 horizontal_resolution_px() const; + void set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); + private: + ::PROTOBUF_NAMESPACE_ID::uint32 _internal_horizontal_resolution_px() const; + void _internal_set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); + public: + + // uint32 vertical_resolution_px = 7; + void clear_vertical_resolution_px(); + ::PROTOBUF_NAMESPACE_ID::uint32 vertical_resolution_px() const; + void set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); + private: + ::PROTOBUF_NAMESPACE_ID::uint32 _internal_vertical_resolution_px() const; + void _internal_set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); + public: + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; + float focal_length_mm_; + float horizontal_sensor_size_mm_; + float vertical_sensor_size_mm_; + ::PROTOBUF_NAMESPACE_ID::uint32 horizontal_resolution_px_; + ::PROTOBUF_NAMESPACE_ID::uint32 vertical_resolution_px_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class Position final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Position) */ { + public: + inline Position() : Position(nullptr) {} + ~Position() override; + explicit constexpr Position(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Position(const Position& from); + Position(Position&& from) noexcept + : Position() { + *this = ::std::move(from); + } + + inline Position& operator=(const Position& from) { + CopyFrom(from); + return *this; + } + inline Position& operator=(Position&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const Position& default_instance() { + return *internal_default_instance(); + } + static inline const Position* internal_default_instance() { + return reinterpret_cast( + &_Position_default_instance_); + } + static constexpr int kIndexInFileMessages = + 9; + + friend void swap(Position& a, Position& b) { + a.Swap(&b); + } + inline void Swap(Position* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Position* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline Position* New() const final { + return new Position(); + } + + Position* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Position& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const Position& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Position* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.Position"; + } + protected: + explicit Position(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAbsoluteAltitudeMFieldNumber = 3, + kRelativeAltitudeMFieldNumber = 4, + }; + // 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); + 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; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + double latitude_deg_; + double longitude_deg_; + float absolute_altitude_m_; + float relative_altitude_m_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class Quaternion final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Quaternion) */ { + public: + inline Quaternion() : Quaternion(nullptr) {} + ~Quaternion() override; + explicit constexpr Quaternion(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Quaternion(const Quaternion& from); + Quaternion(Quaternion&& from) noexcept + : Quaternion() { + *this = ::std::move(from); + } + + inline Quaternion& operator=(const Quaternion& from) { + CopyFrom(from); + return *this; + } + inline Quaternion& operator=(Quaternion&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const Quaternion& default_instance() { + return *internal_default_instance(); + } + static inline const Quaternion* internal_default_instance() { + return reinterpret_cast( + &_Quaternion_default_instance_); + } + static constexpr int kIndexInFileMessages = + 10; + + friend void swap(Quaternion& a, Quaternion& b) { + a.Swap(&b); + } + inline void Swap(Quaternion* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Quaternion* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline Quaternion* New() const final { + return new Quaternion(); + } + + Quaternion* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Quaternion& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const Quaternion& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Quaternion* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.Quaternion"; + } + protected: + explicit Quaternion(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kWFieldNumber = 1, + kXFieldNumber = 2, + kYFieldNumber = 3, + kZFieldNumber = 4, + }; + // 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); + 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; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + float w_; + float x_; + float y_; + float z_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class CaptureInfo final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureInfo) */ { + public: + inline CaptureInfo() : CaptureInfo(nullptr) {} + ~CaptureInfo() override; + explicit constexpr CaptureInfo(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + CaptureInfo(const CaptureInfo& 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 (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::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 = + 11; + + friend void swap(CaptureInfo& a, CaptureInfo& b) { + a.Swap(&b); + } + inline void Swap(CaptureInfo* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(CaptureInfo* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline CaptureInfo* New() const final { + return new CaptureInfo(); + } + + CaptureInfo* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const CaptureInfo& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const CaptureInfo& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CaptureInfo* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.CaptureInfo"; + } + protected: + explicit CaptureInfo(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::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(ArgT0&& arg0, ArgT... args); + std::string* mutable_file_url(); + PROTOBUF_MUST_USE_RESULT std::string* release_file_url(); + void set_allocated_file_url(std::string* file_url); + 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; + private: + bool _internal_has_position() const; + public: + void clear_position(); + const ::mavsdk::rpc::camera_server::Position& position() const; + PROTOBUF_MUST_USE_RESULT ::mavsdk::rpc::camera_server::Position* release_position(); + ::mavsdk::rpc::camera_server::Position* mutable_position(); + void set_allocated_position(::mavsdk::rpc::camera_server::Position* position); + private: + const ::mavsdk::rpc::camera_server::Position& _internal_position() const; + ::mavsdk::rpc::camera_server::Position* _internal_mutable_position(); + public: + void unsafe_arena_set_allocated_position( + ::mavsdk::rpc::camera_server::Position* position); + ::mavsdk::rpc::camera_server::Position* unsafe_arena_release_position(); + + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + bool has_attitude_quaternion() const; + private: + bool _internal_has_attitude_quaternion() const; + public: + void clear_attitude_quaternion(); + const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion() const; + PROTOBUF_MUST_USE_RESULT ::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* attitude_quaternion); + private: + const ::mavsdk::rpc::camera_server::Quaternion& _internal_attitude_quaternion() const; + ::mavsdk::rpc::camera_server::Quaternion* _internal_mutable_attitude_quaternion(); + public: + void unsafe_arena_set_allocated_attitude_quaternion( + ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); + ::mavsdk::rpc::camera_server::Quaternion* unsafe_arena_release_attitude_quaternion(); + + // uint64 time_utc_us = 3; + void clear_time_utc_us(); + ::PROTOBUF_NAMESPACE_ID::uint64 time_utc_us() const; + void set_time_utc_us(::PROTOBUF_NAMESPACE_ID::uint64 value); + private: + ::PROTOBUF_NAMESPACE_ID::uint64 _internal_time_utc_us() const; + void _internal_set_time_utc_us(::PROTOBUF_NAMESPACE_ID::uint64 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(); + ::PROTOBUF_NAMESPACE_ID::int32 index() const; + void set_index(::PROTOBUF_NAMESPACE_ID::int32 value); + private: + ::PROTOBUF_NAMESPACE_ID::int32 _internal_index() const; + void _internal_set_index(::PROTOBUF_NAMESPACE_ID::int32 value); + public: + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureInfo) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr file_url_; + ::mavsdk::rpc::camera_server::Position* position_; + ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion_; + ::PROTOBUF_NAMESPACE_ID::uint64 time_utc_us_; + bool is_success_; + ::PROTOBUF_NAMESPACE_ID::int32 index_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class CameraServerResult final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CameraServerResult) */ { + public: + inline CameraServerResult() : CameraServerResult(nullptr) {} + ~CameraServerResult() override; + explicit constexpr CameraServerResult(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + CameraServerResult(const CameraServerResult& from); + CameraServerResult(CameraServerResult&& from) noexcept + : CameraServerResult() { + *this = ::std::move(from); + } + + inline CameraServerResult& operator=(const CameraServerResult& from) { + CopyFrom(from); + return *this; + } + inline CameraServerResult& operator=(CameraServerResult&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const CameraServerResult& default_instance() { + return *internal_default_instance(); + } + static inline const CameraServerResult* internal_default_instance() { + return reinterpret_cast( + &_CameraServerResult_default_instance_); + } + static constexpr int kIndexInFileMessages = + 12; + + friend void swap(CameraServerResult& a, CameraServerResult& b) { + a.Swap(&b); + } + inline void Swap(CameraServerResult* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(CameraServerResult* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline CameraServerResult* New() const final { + return new CameraServerResult(); + } + + CameraServerResult* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const CameraServerResult& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const CameraServerResult& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CameraServerResult* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.camera_server.CameraServerResult"; + } + protected: + explicit CameraServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef CameraServerResult_Result 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 ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* + Result_descriptor() { + return CameraServerResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T enum_t_value) { + static_assert(::std::is_same::value || + ::std::is_integral::value, + "Incorrect type passed to function Result_Name."); + return CameraServerResult_Result_Name(enum_t_value); + } + static inline bool Result_Parse(::PROTOBUF_NAMESPACE_ID::ConstStringParam name, + Result* value) { + return CameraServerResult_Result_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + enum : int { + kResultStrFieldNumber = 2, + kResultFieldNumber = 1, + }; + // string result_str = 2; + void clear_result_str(); + const std::string& result_str() const; + template + void set_result_str(ArgT0&& arg0, ArgT... args); + std::string* mutable_result_str(); + PROTOBUF_MUST_USE_RESULT std::string* release_result_str(); + void set_allocated_result_str(std::string* result_str); + 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); + 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; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr result_str_; + int result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + 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::_internal_has_information() const { + return this != internal_default_instance() && information_ != nullptr; +} +inline bool SetInformationRequest::has_information() const { + return _internal_has_information(); +} +inline void SetInformationRequest::clear_information() { + if (GetArenaForAllocation() == nullptr && information_ != nullptr) { + delete information_; + } + information_ = nullptr; +} +inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::_internal_information() const { + const ::mavsdk::rpc::camera_server::Information* p = information_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_Information_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::information() const { + // @@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* information) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(information_); + } + information_ = information; + if (information) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInformationRequest.information) +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::release_information() { + + ::mavsdk::rpc::camera_server::Information* temp = information_; + information_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::unsafe_arena_release_information() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationRequest.information) + + ::mavsdk::rpc::camera_server::Information* temp = information_; + information_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::_internal_mutable_information() { + + if (information_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(GetArenaForAllocation()); + information_ = p; + } + return information_; +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::mutable_information() { + ::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* information) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete information_; + } + if (information) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::camera_server::Information>::GetOwningArena(information); + if (message_arena != submessage_arena) { + information = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, information, submessage_arena); + } + + } else { + + } + information_ = information; + // @@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::_internal_has_camera_server_result() const { + return this != internal_default_instance() && camera_server_result_ != nullptr; +} +inline bool SetInformationResponse::has_camera_server_result() const { + return _internal_has_camera_server_result(); +} +inline void SetInformationResponse::clear_camera_server_result() { + if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { + delete camera_server_result_; + } + camera_server_result_ = nullptr; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInformationResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = 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 { + // @@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* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(camera_server_result_); + } + camera_server_result_ = camera_server_result; + if (camera_server_result) { + + } else { + + } + // @@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() { + + ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; + camera_server_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + + ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; + camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::_internal_mutable_camera_server_result() { + + if (camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + camera_server_result_ = p; + } + return camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::mutable_camera_server_result() { + ::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* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::camera_server::CameraServerResult>::GetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + + } else { + + } + camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + +// SetInProgressRequest + +// bool in_progress = 1; +inline void SetInProgressRequest::clear_in_progress() { + in_progress_ = false; +} +inline bool SetInProgressRequest::_internal_in_progress() const { + return in_progress_; +} +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::_internal_set_in_progress(bool value) { + + in_progress_ = value; +} +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) +} + +// ------------------------------------------------------------------- + +// SetInProgressResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool SetInProgressResponse::_internal_has_camera_server_result() const { + return this != internal_default_instance() && camera_server_result_ != nullptr; +} +inline bool SetInProgressResponse::has_camera_server_result() const { + return _internal_has_camera_server_result(); +} +inline void SetInProgressResponse::clear_camera_server_result() { + if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { + delete camera_server_result_; + } + camera_server_result_ = nullptr; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInProgressResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = 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 { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void SetInProgressResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(camera_server_result_); + } + camera_server_result_ = camera_server_result; + if (camera_server_result) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::release_camera_server_result() { + + ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; + camera_server_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + + ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; + camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::_internal_mutable_camera_server_result() { + + if (camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + camera_server_result_ = p; + } + return camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + return _msg; +} +inline void SetInProgressResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::camera_server::CameraServerResult>::GetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + + } else { + + } + camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + +// SubscribeTakePhotoRequest + +// ------------------------------------------------------------------- + +// TakePhotoResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool TakePhotoResponse::_internal_has_camera_server_result() const { + return this != internal_default_instance() && camera_server_result_ != nullptr; +} +inline bool TakePhotoResponse::has_camera_server_result() const { + return _internal_has_camera_server_result(); +} +inline void TakePhotoResponse::clear_camera_server_result() { + if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { + delete camera_server_result_; + } + camera_server_result_ = nullptr; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& TakePhotoResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& TakePhotoResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.TakePhotoResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void TakePhotoResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(camera_server_result_); + } + camera_server_result_ = camera_server_result; + if (camera_server_result) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.TakePhotoResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* TakePhotoResponse::release_camera_server_result() { + + ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; + camera_server_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* TakePhotoResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.TakePhotoResponse.camera_server_result) + + ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; + camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* TakePhotoResponse::_internal_mutable_camera_server_result() { + + if (camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + camera_server_result_ = p; + } + return camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* TakePhotoResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.TakePhotoResponse.camera_server_result) + return _msg; +} +inline void TakePhotoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::camera_server::CameraServerResult>::GetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + + } else { + + } + camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.TakePhotoResponse.camera_server_result) +} + +// int32 index = 2; +inline void TakePhotoResponse::clear_index() { + index_ = 0; +} +inline ::PROTOBUF_NAMESPACE_ID::int32 TakePhotoResponse::_internal_index() const { + return index_; +} +inline ::PROTOBUF_NAMESPACE_ID::int32 TakePhotoResponse::index() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.TakePhotoResponse.index) + return _internal_index(); +} +inline void TakePhotoResponse::_internal_set_index(::PROTOBUF_NAMESPACE_ID::int32 value) { + + index_ = value; +} +inline void TakePhotoResponse::set_index(::PROTOBUF_NAMESPACE_ID::int32 value) { + _internal_set_index(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.TakePhotoResponse.index) +} + +// ------------------------------------------------------------------- + +// PublishPhotoRequest + +// .mavsdk.rpc.camera_server.CaptureInfo capture_info = 1; +inline bool PublishPhotoRequest::_internal_has_capture_info() const { + return this != internal_default_instance() && capture_info_ != nullptr; +} +inline bool PublishPhotoRequest::has_capture_info() const { + return _internal_has_capture_info(); +} +inline void PublishPhotoRequest::clear_capture_info() { + if (GetArenaForAllocation() == nullptr && capture_info_ != nullptr) { + delete capture_info_; + } + capture_info_ = nullptr; +} +inline const ::mavsdk::rpc::camera_server::CaptureInfo& PublishPhotoRequest::_internal_capture_info() const { + const ::mavsdk::rpc::camera_server::CaptureInfo* p = capture_info_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CaptureInfo& PublishPhotoRequest::capture_info() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) + return _internal_capture_info(); +} +inline void PublishPhotoRequest::unsafe_arena_set_allocated_capture_info( + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(capture_info_); + } + capture_info_ = capture_info; + if (capture_info) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) +} +inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::release_capture_info() { + + ::mavsdk::rpc::camera_server::CaptureInfo* temp = capture_info_; + capture_info_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::unsafe_arena_release_capture_info() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) + + ::mavsdk::rpc::camera_server::CaptureInfo* temp = capture_info_; + capture_info_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::_internal_mutable_capture_info() { + + if (capture_info_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(GetArenaForAllocation()); + capture_info_ = p; + } + return capture_info_; +} +inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::mutable_capture_info() { + ::mavsdk::rpc::camera_server::CaptureInfo* _msg = _internal_mutable_capture_info(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) + return _msg; +} +inline void PublishPhotoRequest::set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete capture_info_; + } + if (capture_info) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::camera_server::CaptureInfo>::GetOwningArena(capture_info); + if (message_arena != submessage_arena) { + capture_info = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, capture_info, submessage_arena); + } + + } else { + + } + capture_info_ = capture_info; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) +} + +// ------------------------------------------------------------------- + +// PublishPhotoResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool PublishPhotoResponse::_internal_has_camera_server_result() const { + return this != internal_default_instance() && camera_server_result_ != nullptr; +} +inline bool PublishPhotoResponse::has_camera_server_result() const { + return _internal_has_camera_server_result(); +} +inline void PublishPhotoResponse::clear_camera_server_result() { + if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { + delete camera_server_result_; + } + camera_server_result_ = nullptr; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& PublishPhotoResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& PublishPhotoResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void PublishPhotoResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(camera_server_result_); + } + camera_server_result_ = camera_server_result; + if (camera_server_result) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::release_camera_server_result() { + + ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; + camera_server_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) + + ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; + camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::_internal_mutable_camera_server_result() { + + if (camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + camera_server_result_ = p; + } + return camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) + return _msg; +} +inline void PublishPhotoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::camera_server::CameraServerResult>::GetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + + } else { + + } + camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + +// Information + +// string vendor_name = 1; +inline void Information::clear_vendor_name() { + vendor_name_.ClearToEmpty(); +} +inline const std::string& Information::vendor_name() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.vendor_name) + return _internal_vendor_name(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void Information::set_vendor_name(ArgT0&& arg0, ArgT... args) { + + vendor_name_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.vendor_name) +} +inline std::string* Information::mutable_vendor_name() { + std::string* _s = _internal_mutable_vendor_name(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.Information.vendor_name) + return _s; +} +inline const std::string& Information::_internal_vendor_name() const { + return vendor_name_.Get(); +} +inline void Information::_internal_set_vendor_name(const std::string& value) { + + vendor_name_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* Information::_internal_mutable_vendor_name() { + + return vendor_name_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* Information::release_vendor_name() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.Information.vendor_name) + return vendor_name_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void Information::set_allocated_vendor_name(std::string* vendor_name) { + if (vendor_name != nullptr) { + + } else { + + } + vendor_name_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), vendor_name, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.vendor_name) +} + +// string model_name = 2; +inline void Information::clear_model_name() { + model_name_.ClearToEmpty(); +} +inline const std::string& Information::model_name() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.model_name) + return _internal_model_name(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void Information::set_model_name(ArgT0&& arg0, ArgT... args) { + + model_name_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.model_name) +} +inline std::string* Information::mutable_model_name() { + std::string* _s = _internal_mutable_model_name(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.Information.model_name) + return _s; +} +inline const std::string& Information::_internal_model_name() const { + return model_name_.Get(); +} +inline void Information::_internal_set_model_name(const std::string& value) { + + model_name_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* Information::_internal_mutable_model_name() { + + return model_name_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* Information::release_model_name() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.Information.model_name) + return model_name_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void Information::set_allocated_model_name(std::string* model_name) { + if (model_name != nullptr) { + + } else { + + } + model_name_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), model_name, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.model_name) +} + +// float focal_length_mm = 3; +inline void Information::clear_focal_length_mm() { + focal_length_mm_ = 0; +} +inline float Information::_internal_focal_length_mm() const { + return focal_length_mm_; +} +inline float Information::focal_length_mm() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.focal_length_mm) + return _internal_focal_length_mm(); +} +inline void Information::_internal_set_focal_length_mm(float value) { + + focal_length_mm_ = value; +} +inline void Information::set_focal_length_mm(float value) { + _internal_set_focal_length_mm(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.focal_length_mm) +} + +// float horizontal_sensor_size_mm = 4; +inline void Information::clear_horizontal_sensor_size_mm() { + horizontal_sensor_size_mm_ = 0; +} +inline float Information::_internal_horizontal_sensor_size_mm() const { + return horizontal_sensor_size_mm_; +} +inline float Information::horizontal_sensor_size_mm() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.horizontal_sensor_size_mm) + return _internal_horizontal_sensor_size_mm(); +} +inline void Information::_internal_set_horizontal_sensor_size_mm(float value) { + + horizontal_sensor_size_mm_ = value; +} +inline void Information::set_horizontal_sensor_size_mm(float value) { + _internal_set_horizontal_sensor_size_mm(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.horizontal_sensor_size_mm) +} + +// float vertical_sensor_size_mm = 5; +inline void Information::clear_vertical_sensor_size_mm() { + vertical_sensor_size_mm_ = 0; +} +inline float Information::_internal_vertical_sensor_size_mm() const { + return vertical_sensor_size_mm_; +} +inline float Information::vertical_sensor_size_mm() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.vertical_sensor_size_mm) + return _internal_vertical_sensor_size_mm(); +} +inline void Information::_internal_set_vertical_sensor_size_mm(float value) { + + vertical_sensor_size_mm_ = value; +} +inline void Information::set_vertical_sensor_size_mm(float value) { + _internal_set_vertical_sensor_size_mm(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.vertical_sensor_size_mm) +} + +// uint32 horizontal_resolution_px = 6; +inline void Information::clear_horizontal_resolution_px() { + horizontal_resolution_px_ = 0u; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::_internal_horizontal_resolution_px() const { + return horizontal_resolution_px_; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::horizontal_resolution_px() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.horizontal_resolution_px) + return _internal_horizontal_resolution_px(); +} +inline void Information::_internal_set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value) { + + horizontal_resolution_px_ = value; +} +inline void Information::set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value) { + _internal_set_horizontal_resolution_px(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.horizontal_resolution_px) +} + +// uint32 vertical_resolution_px = 7; +inline void Information::clear_vertical_resolution_px() { + vertical_resolution_px_ = 0u; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::_internal_vertical_resolution_px() const { + return vertical_resolution_px_; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::vertical_resolution_px() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.vertical_resolution_px) + return _internal_vertical_resolution_px(); +} +inline void Information::_internal_set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value) { + + vertical_resolution_px_ = value; +} +inline void Information::set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value) { + _internal_set_vertical_resolution_px(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.vertical_resolution_px) +} + +// ------------------------------------------------------------------- + +// Position + +// double latitude_deg = 1; +inline void Position::clear_latitude_deg() { + latitude_deg_ = 0; +} +inline double Position::_internal_latitude_deg() const { + return latitude_deg_; +} +inline double Position::latitude_deg() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Position.latitude_deg) + return _internal_latitude_deg(); +} +inline void Position::_internal_set_latitude_deg(double value) { + + latitude_deg_ = value; +} +inline void Position::set_latitude_deg(double value) { + _internal_set_latitude_deg(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Position.latitude_deg) +} + +// double longitude_deg = 2; +inline void Position::clear_longitude_deg() { + longitude_deg_ = 0; +} +inline double Position::_internal_longitude_deg() const { + return longitude_deg_; +} +inline double Position::longitude_deg() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Position.longitude_deg) + return _internal_longitude_deg(); +} +inline void Position::_internal_set_longitude_deg(double value) { + + longitude_deg_ = value; +} +inline void Position::set_longitude_deg(double value) { + _internal_set_longitude_deg(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Position.longitude_deg) +} + +// float absolute_altitude_m = 3; +inline void Position::clear_absolute_altitude_m() { + absolute_altitude_m_ = 0; +} +inline float Position::_internal_absolute_altitude_m() const { + return absolute_altitude_m_; +} +inline float Position::absolute_altitude_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Position.absolute_altitude_m) + return _internal_absolute_altitude_m(); +} +inline void Position::_internal_set_absolute_altitude_m(float value) { + + absolute_altitude_m_ = value; +} +inline void Position::set_absolute_altitude_m(float value) { + _internal_set_absolute_altitude_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Position.absolute_altitude_m) +} + +// float relative_altitude_m = 4; +inline void Position::clear_relative_altitude_m() { + relative_altitude_m_ = 0; +} +inline float Position::_internal_relative_altitude_m() const { + return relative_altitude_m_; +} +inline float Position::relative_altitude_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Position.relative_altitude_m) + return _internal_relative_altitude_m(); +} +inline void Position::_internal_set_relative_altitude_m(float value) { + + relative_altitude_m_ = value; +} +inline void Position::set_relative_altitude_m(float value) { + _internal_set_relative_altitude_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Position.relative_altitude_m) +} + +// ------------------------------------------------------------------- + +// Quaternion + +// float w = 1; +inline void Quaternion::clear_w() { + w_ = 0; +} +inline float Quaternion::_internal_w() const { + return w_; +} +inline float Quaternion::w() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Quaternion.w) + return _internal_w(); +} +inline void Quaternion::_internal_set_w(float value) { + + w_ = value; +} +inline void Quaternion::set_w(float value) { + _internal_set_w(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Quaternion.w) +} + +// float x = 2; +inline void Quaternion::clear_x() { + x_ = 0; +} +inline float Quaternion::_internal_x() const { + return x_; +} +inline float Quaternion::x() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Quaternion.x) + return _internal_x(); +} +inline void Quaternion::_internal_set_x(float value) { + + x_ = value; +} +inline void Quaternion::set_x(float value) { + _internal_set_x(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Quaternion.x) +} + +// float y = 3; +inline void Quaternion::clear_y() { + y_ = 0; +} +inline float Quaternion::_internal_y() const { + return y_; +} +inline float Quaternion::y() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Quaternion.y) + return _internal_y(); +} +inline void Quaternion::_internal_set_y(float value) { + + y_ = value; +} +inline void Quaternion::set_y(float value) { + _internal_set_y(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Quaternion.y) +} + +// float z = 4; +inline void Quaternion::clear_z() { + z_ = 0; +} +inline float Quaternion::_internal_z() const { + return z_; +} +inline float Quaternion::z() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Quaternion.z) + return _internal_z(); +} +inline void Quaternion::_internal_set_z(float value) { + + z_ = value; +} +inline void Quaternion::set_z(float value) { + _internal_set_z(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Quaternion.z) +} + +// ------------------------------------------------------------------- + +// CaptureInfo + +// .mavsdk.rpc.camera_server.Position position = 1; +inline bool CaptureInfo::_internal_has_position() const { + return this != internal_default_instance() && position_ != nullptr; +} +inline bool CaptureInfo::has_position() const { + return _internal_has_position(); +} +inline void CaptureInfo::clear_position() { + if (GetArenaForAllocation() == nullptr && position_ != nullptr) { + delete position_; + } + position_ = nullptr; +} +inline const ::mavsdk::rpc::camera_server::Position& CaptureInfo::_internal_position() const { + const ::mavsdk::rpc::camera_server::Position* p = position_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_Position_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::Position& CaptureInfo::position() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureInfo.position) + return _internal_position(); +} +inline void CaptureInfo::unsafe_arena_set_allocated_position( + ::mavsdk::rpc::camera_server::Position* position) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(position_); + } + position_ = position; + if (position) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.CaptureInfo.position) +} +inline ::mavsdk::rpc::camera_server::Position* CaptureInfo::release_position() { + + ::mavsdk::rpc::camera_server::Position* temp = position_; + position_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::camera_server::Position* CaptureInfo::unsafe_arena_release_position() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.CaptureInfo.position) + + ::mavsdk::rpc::camera_server::Position* temp = position_; + position_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::Position* CaptureInfo::_internal_mutable_position() { + + if (position_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::Position>(GetArenaForAllocation()); + position_ = p; + } + return position_; +} +inline ::mavsdk::rpc::camera_server::Position* CaptureInfo::mutable_position() { + ::mavsdk::rpc::camera_server::Position* _msg = _internal_mutable_position(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.CaptureInfo.position) + return _msg; +} +inline void CaptureInfo::set_allocated_position(::mavsdk::rpc::camera_server::Position* position) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete position_; + } + if (position) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::camera_server::Position>::GetOwningArena(position); + if (message_arena != submessage_arena) { + position = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, position, submessage_arena); + } + + } else { + + } + position_ = position; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.CaptureInfo.position) +} + +// .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; +inline bool CaptureInfo::_internal_has_attitude_quaternion() const { + return this != internal_default_instance() && attitude_quaternion_ != nullptr; +} +inline bool CaptureInfo::has_attitude_quaternion() const { + return _internal_has_attitude_quaternion(); +} +inline void CaptureInfo::clear_attitude_quaternion() { + if (GetArenaForAllocation() == nullptr && attitude_quaternion_ != nullptr) { + delete attitude_quaternion_; + } + attitude_quaternion_ = nullptr; +} +inline const ::mavsdk::rpc::camera_server::Quaternion& CaptureInfo::_internal_attitude_quaternion() const { + const ::mavsdk::rpc::camera_server::Quaternion* p = attitude_quaternion_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_Quaternion_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::Quaternion& CaptureInfo::attitude_quaternion() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureInfo.attitude_quaternion) + return _internal_attitude_quaternion(); +} +inline void CaptureInfo::unsafe_arena_set_allocated_attitude_quaternion( + ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(attitude_quaternion_); + } + attitude_quaternion_ = attitude_quaternion; + if (attitude_quaternion) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.CaptureInfo.attitude_quaternion) +} +inline ::mavsdk::rpc::camera_server::Quaternion* CaptureInfo::release_attitude_quaternion() { + + ::mavsdk::rpc::camera_server::Quaternion* temp = attitude_quaternion_; + attitude_quaternion_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::camera_server::Quaternion* CaptureInfo::unsafe_arena_release_attitude_quaternion() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.CaptureInfo.attitude_quaternion) + + ::mavsdk::rpc::camera_server::Quaternion* temp = attitude_quaternion_; + attitude_quaternion_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::Quaternion* CaptureInfo::_internal_mutable_attitude_quaternion() { + + if (attitude_quaternion_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::Quaternion>(GetArenaForAllocation()); + attitude_quaternion_ = p; + } + return attitude_quaternion_; +} +inline ::mavsdk::rpc::camera_server::Quaternion* CaptureInfo::mutable_attitude_quaternion() { + ::mavsdk::rpc::camera_server::Quaternion* _msg = _internal_mutable_attitude_quaternion(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.CaptureInfo.attitude_quaternion) + return _msg; +} +inline void CaptureInfo::set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete attitude_quaternion_; + } + if (attitude_quaternion) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::camera_server::Quaternion>::GetOwningArena(attitude_quaternion); + if (message_arena != submessage_arena) { + attitude_quaternion = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, attitude_quaternion, submessage_arena); + } + + } else { + + } + attitude_quaternion_ = attitude_quaternion; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.CaptureInfo.attitude_quaternion) +} + +// uint64 time_utc_us = 3; +inline void CaptureInfo::clear_time_utc_us() { + time_utc_us_ = uint64_t{0u}; +} +inline ::PROTOBUF_NAMESPACE_ID::uint64 CaptureInfo::_internal_time_utc_us() const { + return time_utc_us_; +} +inline ::PROTOBUF_NAMESPACE_ID::uint64 CaptureInfo::time_utc_us() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureInfo.time_utc_us) + return _internal_time_utc_us(); +} +inline void CaptureInfo::_internal_set_time_utc_us(::PROTOBUF_NAMESPACE_ID::uint64 value) { + + time_utc_us_ = value; +} +inline void CaptureInfo::set_time_utc_us(::PROTOBUF_NAMESPACE_ID::uint64 value) { + _internal_set_time_utc_us(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureInfo.time_utc_us) +} + +// bool is_success = 4; +inline void CaptureInfo::clear_is_success() { + is_success_ = false; +} +inline bool CaptureInfo::_internal_is_success() const { + return is_success_; +} +inline bool CaptureInfo::is_success() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureInfo.is_success) + return _internal_is_success(); +} +inline void CaptureInfo::_internal_set_is_success(bool value) { + + is_success_ = value; +} +inline void CaptureInfo::set_is_success(bool value) { + _internal_set_is_success(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureInfo.is_success) +} + +// int32 index = 5; +inline void CaptureInfo::clear_index() { + index_ = 0; +} +inline ::PROTOBUF_NAMESPACE_ID::int32 CaptureInfo::_internal_index() const { + return index_; +} +inline ::PROTOBUF_NAMESPACE_ID::int32 CaptureInfo::index() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureInfo.index) + return _internal_index(); +} +inline void CaptureInfo::_internal_set_index(::PROTOBUF_NAMESPACE_ID::int32 value) { + + index_ = value; +} +inline void CaptureInfo::set_index(::PROTOBUF_NAMESPACE_ID::int32 value) { + _internal_set_index(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureInfo.index) +} + +// string file_url = 6; +inline void CaptureInfo::clear_file_url() { + file_url_.ClearToEmpty(); +} +inline const std::string& CaptureInfo::file_url() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureInfo.file_url) + return _internal_file_url(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void CaptureInfo::set_file_url(ArgT0&& arg0, ArgT... args) { + + file_url_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureInfo.file_url) +} +inline std::string* CaptureInfo::mutable_file_url() { + std::string* _s = _internal_mutable_file_url(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.CaptureInfo.file_url) + return _s; +} +inline const std::string& CaptureInfo::_internal_file_url() const { + return file_url_.Get(); +} +inline void CaptureInfo::_internal_set_file_url(const std::string& value) { + + file_url_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* CaptureInfo::_internal_mutable_file_url() { + + return file_url_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* CaptureInfo::release_file_url() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.CaptureInfo.file_url) + return file_url_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void CaptureInfo::set_allocated_file_url(std::string* file_url) { + if (file_url != nullptr) { + + } else { + + } + file_url_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), file_url, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.CaptureInfo.file_url) +} + +// ------------------------------------------------------------------- + +// CameraServerResult + +// .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; +inline void CameraServerResult::clear_result() { + result_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult_Result CameraServerResult::_internal_result() const { + return static_cast< ::mavsdk::rpc::camera_server::CameraServerResult_Result >(result_); +} +inline ::mavsdk::rpc::camera_server::CameraServerResult_Result CameraServerResult::result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CameraServerResult.result) + return _internal_result(); +} +inline void CameraServerResult::_internal_set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value) { + + result_ = value; +} +inline void CameraServerResult::set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value) { + _internal_set_result(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CameraServerResult.result) +} + +// string result_str = 2; +inline void CameraServerResult::clear_result_str() { + result_str_.ClearToEmpty(); +} +inline const std::string& CameraServerResult::result_str() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CameraServerResult.result_str) + return _internal_result_str(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void CameraServerResult::set_result_str(ArgT0&& arg0, ArgT... args) { + + result_str_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CameraServerResult.result_str) +} +inline std::string* CameraServerResult::mutable_result_str() { + std::string* _s = _internal_mutable_result_str(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.CameraServerResult.result_str) + return _s; +} +inline const std::string& CameraServerResult::_internal_result_str() const { + return result_str_.Get(); +} +inline void CameraServerResult::_internal_set_result_str(const std::string& value) { + + result_str_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* CameraServerResult::_internal_mutable_result_str() { + + return result_str_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* CameraServerResult::release_result_str() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.CameraServerResult.result_str) + return result_str_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void CameraServerResult::set_allocated_result_str(std::string* result_str) { + if (result_str != nullptr) { + + } else { + + } + result_str_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), result_str, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.CameraServerResult.result_str) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace camera_server +} // namespace rpc +} // namespace mavsdk + +PROTOBUF_NAMESPACE_OPEN + +template <> struct is_proto_enum< ::mavsdk::rpc::camera_server::CameraServerResult_Result> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::mavsdk::rpc::camera_server::CameraServerResult_Result>() { + return ::mavsdk::rpc::camera_server::CameraServerResult_Result_descriptor(); +} + +PROTOBUF_NAMESPACE_CLOSE + +// @@protoc_insertion_point(global_scope) + +#include +#endif // GOOGLE_PROTOBUF_INCLUDED_GOOGLE_PROTOBUF_INCLUDED_camera_5fserver_2fcamera_5fserver_2eproto diff --git a/src/mavsdk_server/src/grpc_server.cpp b/src/mavsdk_server/src/grpc_server.cpp index 4745132a40..e80741eb7f 100644 --- a/src/mavsdk_server/src/grpc_server.cpp +++ b/src/mavsdk_server/src/grpc_server.cpp @@ -23,6 +23,7 @@ int GrpcServer::run() builder.RegisterService(&_action_server_service); builder.RegisterService(&_calibration_service); builder.RegisterService(&_camera_service); + builder.RegisterService(&_camera_server_service); builder.RegisterService(&_failure_service); builder.RegisterService(&_follow_me_service); builder.RegisterService(&_ftp_service); @@ -75,6 +76,7 @@ void GrpcServer::stop() _action_server_service.stop(); _calibration_service.stop(); _camera_service.stop(); + _camera_server_service.stop(); _failure_service.stop(); _follow_me_service.stop(); _ftp_service.stop(); diff --git a/src/mavsdk_server/src/grpc_server.h b/src/mavsdk_server/src/grpc_server.h index 1bfaeead43..d78ee236f8 100644 --- a/src/mavsdk_server/src/grpc_server.h +++ b/src/mavsdk_server/src/grpc_server.h @@ -14,6 +14,8 @@ #include "calibration/calibration_service_impl.h" #include "plugins/camera/camera.h" #include "camera/camera_service_impl.h" +#include "plugins/camera_server/camera_server.h" +#include "camera_server/camera_server_service_impl.h" #include "plugins/failure/failure.h" #include "failure/failure_service_impl.h" #include "plugins/follow_me/follow_me.h" @@ -74,6 +76,8 @@ class GrpcServer { _calibration_service(_calibration_lazy_plugin), _camera_lazy_plugin(mavsdk), _camera_service(_camera_lazy_plugin), + _camera_server_lazy_plugin(mavsdk), + _camera_server_service(_camera_server_lazy_plugin), _failure_lazy_plugin(mavsdk), _failure_service(_failure_lazy_plugin), _follow_me_lazy_plugin(mavsdk), @@ -137,6 +141,8 @@ class GrpcServer { CalibrationServiceImpl<> _calibration_service; LazyPlugin _camera_lazy_plugin; CameraServiceImpl<> _camera_service; + LazyPlugin _camera_server_lazy_plugin; + CameraServerServiceImpl<> _camera_server_service; LazyPlugin _failure_lazy_plugin; FailureServiceImpl<> _failure_service; LazyPlugin _follow_me_lazy_plugin; 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 new file mode 100644 index 0000000000..2308e1ba6f --- /dev/null +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -0,0 +1,427 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see +// https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/camera_server/camera_server.proto) + +#include "camera_server/camera_server.grpc.pb.h" +#include "plugins/camera_server/camera_server.h" + +#include "mavsdk.h" +#include "lazy_plugin.h" +#include "log.h" +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace mavsdk_server { + +template> +class CameraServerServiceImpl final : public rpc::camera_server::CameraServerService::Service { +public: + CameraServerServiceImpl(LazyPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) {} + + template + void fillResponseWithResult(ResponseType* response, mavsdk::CameraServer::Result& result) const + { + auto rpc_result = translateToRpcResult(result); + + auto* rpc_camera_server_result = new rpc::camera_server::CameraServerResult(); + rpc_camera_server_result->set_result(rpc_result); + std::stringstream ss; + ss << result; + rpc_camera_server_result->set_result_str(ss.str()); + + response->set_allocated_camera_server_result(rpc_camera_server_result); + } + + static std::unique_ptr + translateToRpcInformation(const mavsdk::CameraServer::Information& information) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_vendor_name(information.vendor_name); + + rpc_obj->set_model_name(information.model_name); + + rpc_obj->set_focal_length_mm(information.focal_length_mm); + + rpc_obj->set_horizontal_sensor_size_mm(information.horizontal_sensor_size_mm); + + rpc_obj->set_vertical_sensor_size_mm(information.vertical_sensor_size_mm); + + rpc_obj->set_horizontal_resolution_px(information.horizontal_resolution_px); + + rpc_obj->set_vertical_resolution_px(information.vertical_resolution_px); + + return rpc_obj; + } + + static mavsdk::CameraServer::Information + translateFromRpcInformation(const rpc::camera_server::Information& information) + { + mavsdk::CameraServer::Information obj; + + obj.vendor_name = information.vendor_name(); + + obj.model_name = information.model_name(); + + obj.focal_length_mm = information.focal_length_mm(); + + obj.horizontal_sensor_size_mm = information.horizontal_sensor_size_mm(); + + obj.vertical_sensor_size_mm = information.vertical_sensor_size_mm(); + + obj.horizontal_resolution_px = information.horizontal_resolution_px(); + + obj.vertical_resolution_px = information.vertical_resolution_px(); + + return obj; + } + + static std::unique_ptr + translateToRpcPosition(const mavsdk::CameraServer::Position& position) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_latitude_deg(position.latitude_deg); + + rpc_obj->set_longitude_deg(position.longitude_deg); + + rpc_obj->set_absolute_altitude_m(position.absolute_altitude_m); + + rpc_obj->set_relative_altitude_m(position.relative_altitude_m); + + return rpc_obj; + } + + static mavsdk::CameraServer::Position + translateFromRpcPosition(const rpc::camera_server::Position& position) + { + mavsdk::CameraServer::Position obj; + + obj.latitude_deg = position.latitude_deg(); + + obj.longitude_deg = position.longitude_deg(); + + obj.absolute_altitude_m = position.absolute_altitude_m(); + + obj.relative_altitude_m = position.relative_altitude_m(); + + return obj; + } + + static std::unique_ptr + translateToRpcQuaternion(const mavsdk::CameraServer::Quaternion& quaternion) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_w(quaternion.w); + + rpc_obj->set_x(quaternion.x); + + rpc_obj->set_y(quaternion.y); + + rpc_obj->set_z(quaternion.z); + + return rpc_obj; + } + + static mavsdk::CameraServer::Quaternion + translateFromRpcQuaternion(const rpc::camera_server::Quaternion& quaternion) + { + mavsdk::CameraServer::Quaternion obj; + + obj.w = quaternion.w(); + + obj.x = quaternion.x(); + + obj.y = quaternion.y(); + + obj.z = quaternion.z(); + + return obj; + } + + static std::unique_ptr + translateToRpcCaptureInfo(const mavsdk::CameraServer::CaptureInfo& capture_info) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_allocated_position(translateToRpcPosition(capture_info.position).release()); + + rpc_obj->set_allocated_attitude_quaternion( + translateToRpcQuaternion(capture_info.attitude_quaternion).release()); + + rpc_obj->set_time_utc_us(capture_info.time_utc_us); + + rpc_obj->set_is_success(capture_info.is_success); + + rpc_obj->set_index(capture_info.index); + + rpc_obj->set_file_url(capture_info.file_url); + + return rpc_obj; + } + + static mavsdk::CameraServer::CaptureInfo + translateFromRpcCaptureInfo(const rpc::camera_server::CaptureInfo& capture_info) + { + mavsdk::CameraServer::CaptureInfo obj; + + obj.position = translateFromRpcPosition(capture_info.position()); + + obj.attitude_quaternion = translateFromRpcQuaternion(capture_info.attitude_quaternion()); + + obj.time_utc_us = capture_info.time_utc_us(); + + obj.is_success = capture_info.is_success(); + + obj.index = capture_info.index(); + + obj.file_url = capture_info.file_url(); + + return obj; + } + + static rpc::camera_server::CameraServerResult::Result + translateToRpcResult(const mavsdk::CameraServer::Result& result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case mavsdk::CameraServer::Result::Unknown: + return rpc::camera_server::CameraServerResult_Result_RESULT_UNKNOWN; + case mavsdk::CameraServer::Result::Success: + return rpc::camera_server::CameraServerResult_Result_RESULT_SUCCESS; + case mavsdk::CameraServer::Result::InProgress: + return rpc::camera_server::CameraServerResult_Result_RESULT_IN_PROGRESS; + case mavsdk::CameraServer::Result::Busy: + return rpc::camera_server::CameraServerResult_Result_RESULT_BUSY; + case mavsdk::CameraServer::Result::Denied: + return rpc::camera_server::CameraServerResult_Result_RESULT_DENIED; + case mavsdk::CameraServer::Result::Error: + return rpc::camera_server::CameraServerResult_Result_RESULT_ERROR; + case mavsdk::CameraServer::Result::Timeout: + return rpc::camera_server::CameraServerResult_Result_RESULT_TIMEOUT; + case mavsdk::CameraServer::Result::WrongArgument: + return rpc::camera_server::CameraServerResult_Result_RESULT_WRONG_ARGUMENT; + case mavsdk::CameraServer::Result::NoSystem: + return rpc::camera_server::CameraServerResult_Result_RESULT_NO_SYSTEM; + } + } + + static mavsdk::CameraServer::Result + translateFromRpcResult(const rpc::camera_server::CameraServerResult::Result result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case rpc::camera_server::CameraServerResult_Result_RESULT_UNKNOWN: + return mavsdk::CameraServer::Result::Unknown; + case rpc::camera_server::CameraServerResult_Result_RESULT_SUCCESS: + return mavsdk::CameraServer::Result::Success; + case rpc::camera_server::CameraServerResult_Result_RESULT_IN_PROGRESS: + return mavsdk::CameraServer::Result::InProgress; + case rpc::camera_server::CameraServerResult_Result_RESULT_BUSY: + return mavsdk::CameraServer::Result::Busy; + case rpc::camera_server::CameraServerResult_Result_RESULT_DENIED: + return mavsdk::CameraServer::Result::Denied; + case rpc::camera_server::CameraServerResult_Result_RESULT_ERROR: + return mavsdk::CameraServer::Result::Error; + case rpc::camera_server::CameraServerResult_Result_RESULT_TIMEOUT: + return mavsdk::CameraServer::Result::Timeout; + case rpc::camera_server::CameraServerResult_Result_RESULT_WRONG_ARGUMENT: + return mavsdk::CameraServer::Result::WrongArgument; + case rpc::camera_server::CameraServerResult_Result_RESULT_NO_SYSTEM: + return mavsdk::CameraServer::Result::NoSystem; + } + } + + grpc::Status SetInformation( + grpc::ServerContext* /* context */, + const rpc::camera_server::SetInformationRequest* request, + rpc::camera_server::SetInformationResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::CameraServer::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "SetInformation sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->set_information( + translateFromRpcInformation(request->information())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status SetInProgress( + grpc::ServerContext* /* context */, + const rpc::camera_server::SetInProgressRequest* request, + rpc::camera_server::SetInProgressResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::CameraServer::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "SetInProgress sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->set_in_progress(request->in_progress()); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status SubscribeTakePhoto( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + rpc::camera_server::TakePhotoResponse rpc_response; + auto result = mavsdk::CameraServer::Result::NoSystem; + fillResponseWithResult(&rpc_response, result); + writer->Write(rpc_response); + + 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(); + + _lazy_plugin.maybe_plugin()->subscribe_take_photo( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex]( + mavsdk::CameraServer::Result result, const int32_t take_photo) { + rpc::camera_server::TakePhotoResponse rpc_response; + + rpc_response.set_index(take_photo); + + auto rpc_result = translateToRpcResult(result); + auto* rpc_camera_server_result = new rpc::camera_server::CameraServerResult(); + rpc_camera_server_result->set_result(rpc_result); + std::stringstream ss; + ss << result; + rpc_camera_server_result->set_result_str(ss.str()); + rpc_response.set_allocated_camera_server_result(rpc_camera_server_result); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->subscribe_take_photo(nullptr); + + *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 PublishPhoto( + grpc::ServerContext* /* context */, + const rpc::camera_server::PublishPhotoRequest* request, + rpc::camera_server::PublishPhotoResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::CameraServer::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "PublishPhoto sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->publish_photo( + translateFromRpcCaptureInfo(request->capture_info())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + void stop() + { + _stopped.store(true); + for (auto& prom : _stream_stop_promises) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } + } + +private: + void register_stream_stop_promise(std::weak_ptr> prom) + { + // If we have already stopped, set promise immediately and don't add it to list. + if (_stopped.load()) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } else { + _stream_stop_promises.push_back(prom); + } + } + + void unregister_stream_stop_promise(std::shared_ptr> prom) + { + for (auto it = _stream_stop_promises.begin(); it != _stream_stop_promises.end(); + /* ++it */) { + if (it->lock() == prom) { + it = _stream_stop_promises.erase(it); + } else { + ++it; + } + } + } + + LazyPlugin& _lazy_plugin; + std::atomic _stopped{false}; + std::vector>> _stream_stop_promises{}; +}; + +} // namespace mavsdk_server +} // namespace mavsdk \ No newline at end of file From 2eaefed734a3f14c798c4273c0257fe7a4a2cd5b Mon Sep 17 00:00:00 2001 From: David Lechner Date: Mon, 14 Feb 2022 18:08:19 -0600 Subject: [PATCH 2/6] camera_server: implement take photo --- examples/camera_server/camera_server.cpp | 7 +- proto | 2 +- .../plugins/camera_server/camera_server.cpp | 107 +++---- .../camera_server/camera_server_impl.cpp | 98 +++--- .../camera_server/camera_server_impl.h | 6 +- .../plugins/camera_server/camera_server.h | 75 ++--- .../camera_server/camera_server.grpc.pb.cc | 34 +-- .../camera_server/camera_server.grpc.pb.h | 132 ++++----- .../camera_server/camera_server.pb.cc | 280 +++++++++--------- .../camera_server/camera_server.pb.h | 192 ++++++------ .../camera_server_service_impl.h | 10 +- 11 files changed, 454 insertions(+), 489 deletions(-) diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index d64fe523d6..b25c22282d 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -56,7 +56,7 @@ void handle_per_system_camera(std::shared_ptr system) camera_server->set_in_progress(false); camera_server->subscribe_take_photo( - [&camera_server](CameraServer::Result result, int32_t index) { + [camera_server](CameraServer::Result result, int32_t index) { camera_server->set_in_progress(true); std::cout << "taking a picture..." << std::endl; @@ -75,7 +75,7 @@ void handle_per_system_camera(std::shared_ptr system) camera_server->set_in_progress(false); - camera_server->publish_photo({ + camera_server->respond_take_photo({ .position = position, .attitude_quaternion = attitude, .time_utc_us = static_cast(timestamp), @@ -85,7 +85,8 @@ void handle_per_system_camera(std::shared_ptr system) }); }); - std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") << " system ID " << +system->get_system_id() << std::endl; + std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") << " system ID " + << +system->get_system_id() << std::endl; } int main(int argc, char** argv) diff --git a/proto b/proto index 15bf7f73d2..57f5e7f9d3 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 15bf7f73d2f39ecdd324daace06c2f13860e1508 +Subproject commit 57f5e7f9d3d116fca49b570f2074f3defefcd8aa diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 136c7dea2d..d5e47cc2e5 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -1,6 +1,7 @@ // WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. // Edits need to be made to the proto files -// (see https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/camera_server/camera_server.proto) +// (see +// https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/camera_server/camera_server.proto) #include @@ -14,69 +15,56 @@ using Position = CameraServer::Position; using Quaternion = CameraServer::Quaternion; using CaptureInfo = CameraServer::CaptureInfo; +CameraServer::CameraServer(System& system) : + PluginBase(), + _impl{std::make_unique(system)} +{} - -CameraServer::CameraServer(System& system) : PluginBase(), _impl{std::make_unique(system)} {} - -CameraServer::CameraServer(std::shared_ptr system) : PluginBase(), _impl{std::make_unique(system)} {} +CameraServer::CameraServer(std::shared_ptr system) : + PluginBase(), + _impl{std::make_unique(system)} +{} CameraServer::~CameraServer() {} - - - - CameraServer::Result CameraServer::set_information(Information information) const { return _impl->set_information(information); } - - - - CameraServer::Result CameraServer::set_in_progress(bool in_progress) const { return _impl->set_in_progress(in_progress); } - - void CameraServer::subscribe_take_photo(TakePhotoCallback callback) { _impl->subscribe_take_photo(callback); } - - - - - - -CameraServer::Result CameraServer::publish_photo(CaptureInfo capture_info) const +CameraServer::Result CameraServer::respond_take_photo(CaptureInfo capture_info) const { - return _impl->publish_photo(capture_info); + return _impl->respond_take_photo(capture_info); } - - bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { - return - (rhs.vendor_name == lhs.vendor_name) && - (rhs.model_name == lhs.model_name) && - ((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) || rhs.focal_length_mm == lhs.focal_length_mm) && - ((std::isnan(rhs.horizontal_sensor_size_mm) && std::isnan(lhs.horizontal_sensor_size_mm)) || rhs.horizontal_sensor_size_mm == lhs.horizontal_sensor_size_mm) && - ((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) || rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) && - (rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) && - (rhs.vertical_resolution_px == lhs.vertical_resolution_px); + return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && + ((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) || + rhs.focal_length_mm == lhs.focal_length_mm) && + ((std::isnan(rhs.horizontal_sensor_size_mm) && + std::isnan(lhs.horizontal_sensor_size_mm)) || + rhs.horizontal_sensor_size_mm == lhs.horizontal_sensor_size_mm) && + ((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) || + rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) && + (rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) && + (rhs.vertical_resolution_px == lhs.vertical_resolution_px); } std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information) { str << std::setprecision(15); - str << "information:" << '\n' - << "{\n"; + str << "information:" << '\n' << "{\n"; str << " vendor_name: " << information.vendor_name << '\n'; str << " model_name: " << information.model_name << '\n'; str << " focal_length_mm: " << information.focal_length_mm << '\n'; @@ -88,21 +76,22 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Information const& inf return str; } - bool operator==(const CameraServer::Position& lhs, const CameraServer::Position& rhs) { - return - ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) || rhs.latitude_deg == lhs.latitude_deg) && - ((std::isnan(rhs.longitude_deg) && std::isnan(lhs.longitude_deg)) || rhs.longitude_deg == lhs.longitude_deg) && - ((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) || rhs.absolute_altitude_m == lhs.absolute_altitude_m) && - ((std::isnan(rhs.relative_altitude_m) && std::isnan(lhs.relative_altitude_m)) || rhs.relative_altitude_m == lhs.relative_altitude_m); + return ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) || + rhs.latitude_deg == lhs.latitude_deg) && + ((std::isnan(rhs.longitude_deg) && std::isnan(lhs.longitude_deg)) || + rhs.longitude_deg == lhs.longitude_deg) && + ((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) || + rhs.absolute_altitude_m == lhs.absolute_altitude_m) && + ((std::isnan(rhs.relative_altitude_m) && std::isnan(lhs.relative_altitude_m)) || + rhs.relative_altitude_m == lhs.relative_altitude_m); } std::ostream& operator<<(std::ostream& str, CameraServer::Position const& position) { str << std::setprecision(15); - str << "position:" << '\n' - << "{\n"; + str << "position:" << '\n' << "{\n"; str << " latitude_deg: " << position.latitude_deg << '\n'; str << " longitude_deg: " << position.longitude_deg << '\n'; str << " absolute_altitude_m: " << position.absolute_altitude_m << '\n'; @@ -111,21 +100,18 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Position const& positi return str; } - bool operator==(const CameraServer::Quaternion& lhs, const CameraServer::Quaternion& rhs) { - return - ((std::isnan(rhs.w) && std::isnan(lhs.w)) || rhs.w == lhs.w) && - ((std::isnan(rhs.x) && std::isnan(lhs.x)) || rhs.x == lhs.x) && - ((std::isnan(rhs.y) && std::isnan(lhs.y)) || rhs.y == lhs.y) && - ((std::isnan(rhs.z) && std::isnan(lhs.z)) || rhs.z == lhs.z); + return ((std::isnan(rhs.w) && std::isnan(lhs.w)) || rhs.w == lhs.w) && + ((std::isnan(rhs.x) && std::isnan(lhs.x)) || rhs.x == lhs.x) && + ((std::isnan(rhs.y) && std::isnan(lhs.y)) || rhs.y == lhs.y) && + ((std::isnan(rhs.z) && std::isnan(lhs.z)) || rhs.z == lhs.z); } std::ostream& operator<<(std::ostream& str, CameraServer::Quaternion const& quaternion) { str << std::setprecision(15); - str << "quaternion:" << '\n' - << "{\n"; + str << "quaternion:" << '\n' << "{\n"; str << " w: " << quaternion.w << '\n'; str << " x: " << quaternion.x << '\n'; str << " y: " << quaternion.y << '\n'; @@ -134,23 +120,17 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Quaternion const& quat return str; } - bool operator==(const CameraServer::CaptureInfo& lhs, const CameraServer::CaptureInfo& rhs) { - return - (rhs.position == lhs.position) && - (rhs.attitude_quaternion == lhs.attitude_quaternion) && - (rhs.time_utc_us == lhs.time_utc_us) && - (rhs.is_success == lhs.is_success) && - (rhs.index == lhs.index) && - (rhs.file_url == lhs.file_url); + return (rhs.position == lhs.position) && (rhs.attitude_quaternion == lhs.attitude_quaternion) && + (rhs.time_utc_us == lhs.time_utc_us) && (rhs.is_success == lhs.is_success) && + (rhs.index == lhs.index) && (rhs.file_url == lhs.file_url); } std::ostream& operator<<(std::ostream& str, CameraServer::CaptureInfo const& capture_info) { str << std::setprecision(15); - str << "capture_info:" << '\n' - << "{\n"; + str << "capture_info:" << '\n' << "{\n"; str << " position: " << capture_info.position << '\n'; str << " attitude_quaternion: " << capture_info.attitude_quaternion << '\n'; str << " time_utc_us: " << capture_info.time_utc_us << '\n'; @@ -161,8 +141,6 @@ std::ostream& operator<<(std::ostream& str, CameraServer::CaptureInfo const& cap return str; } - - std::ostream& operator<<(std::ostream& str, CameraServer::Result const& result) { switch (result) { @@ -189,7 +167,4 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Result const& result) } } - - - } // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index edc85367ec..08253eac53 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -98,12 +98,6 @@ void CameraServerImpl::init() return process_camera_image_capture_request(command); }, this); - _parent->register_mavlink_command_handler( - MAV_CMD_DO_TRIGGER_CONTROL, - [this](const MavlinkCommandReceiver::CommandLong& command) { - return process_do_trigger_control(command); - }, - this); _parent->register_mavlink_command_handler( MAV_CMD_VIDEO_START_CAPTURE, [this](const MavlinkCommandReceiver::CommandLong& command) { @@ -163,15 +157,41 @@ CameraServer::Result CameraServerImpl::set_in_progress(bool in_progress) void CameraServerImpl::subscribe_take_photo(CameraServer::TakePhotoCallback callback) { - UNUSED(callback); + _take_photo_callback = callback; } -CameraServer::Result CameraServerImpl::publish_photo(CameraServer::CaptureInfo capture_info) +CameraServer::Result CameraServerImpl::respond_take_photo(CameraServer::CaptureInfo capture_info) { - UNUSED(capture_info); + static const uint8_t camera_id = 0; // deprecated unused field + + const float attitude_quaternion[] = { + capture_info.attitude_quaternion.w, + capture_info.attitude_quaternion.x, + capture_info.attitude_quaternion.y, + capture_info.attitude_quaternion.z, + }; - // TODO :) - return {}; + mavlink_message_t msg{}; + mavlink_msg_camera_image_captured_pack( + _parent->get_own_system_id(), + _parent->get_own_component_id(), + &msg, + static_cast(_parent->get_time().elapsed_s() * 1e3), + capture_info.time_utc_us, + camera_id, + capture_info.position.latitude_deg * 1e7, + capture_info.position.longitude_deg * 1e7, + capture_info.position.absolute_altitude_m * 1e3f, + capture_info.position.relative_altitude_m * 1e3f, + attitude_quaternion, + capture_info.index, + capture_info.is_success, + capture_info.file_url.c_str()); + + _parent->send_message(msg); + LogDebug() << "sent camera image captured msg - index: " << +capture_info.index; + + return CameraServer::Result::Success; } std::optional CameraServerImpl::process_camera_information_request( @@ -462,21 +482,47 @@ CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::Comm auto total_images = static_cast(command.params.param3); auto seq_number = static_cast(command.params.param4); - UNUSED(interval); - UNUSED(total_images); - UNUSED(seq_number); + auto current = std::make_shared(total_images == 1 ? seq_number : 1); + auto end = *current + total_images; + auto forever = total_images == 0; - LogDebug() << "unsupported image start capture request"; + LogDebug() << "received image start capture request - interval: " << +interval << " total: " << +total_images << " index: " << +seq_number; - return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + // TODO: validate parameters and return MAV_RESULT_DENIED not valid + + // cancel any previous handler + if (_image_capture_timer_cookie) { + _parent->unregister_timeout_handler(_image_capture_timer_cookie); + _image_capture_timer_cookie = nullptr; + } + + _parent->register_timeout_handler([this, current, end, forever]() { + LogDebug() << "capture image timer triggered"; + + if (_take_photo_callback) { + _take_photo_callback(CameraServer::Result::Success, *current); + } + + if (!forever && ++(*current) >= end) { + _parent->unregister_timeout_handler(_image_capture_timer_cookie); + _image_capture_timer_cookie = nullptr; + } + }, interval, &_image_capture_timer_cookie); + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command) { - LogDebug() << "unsupported image stop capture request"; + LogDebug() << "received image stop capture request"; - return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + if (_image_capture_timer_cookie) { + _parent->unregister_timeout_handler(_image_capture_timer_cookie); + _image_capture_timer_cookie = nullptr; + } + + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional CameraServerImpl::process_camera_image_capture_request( @@ -491,22 +537,6 @@ std::optional CameraServerImpl::process_camera_image_capture_ return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } -std::optional -CameraServerImpl::process_do_trigger_control(const MavlinkCommandReceiver::CommandLong& command) -{ - auto enable = static_cast(command.params.param1); - auto reset = static_cast(command.params.param2); - auto pause = static_cast(command.params.param3); - - UNUSED(enable); - UNUSED(reset); - UNUSED(pause); - - LogDebug() << "unsupported do trigger control request"; - - return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); -} - std::optional CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command) { diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index fc781bd1f4..9a180e44e1 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -22,7 +22,7 @@ class CameraServerImpl : public PluginImplBase { void subscribe_take_photo(CameraServer::TakePhotoCallback callback); - CameraServer::Result publish_photo(CameraServer::CaptureInfo capture_info); + CameraServer::Result respond_take_photo(CameraServer::CaptureInfo capture_info); private: enum StatusFlags { @@ -39,6 +39,8 @@ class CameraServerImpl : public PluginImplBase { bool _is_information_set{}; CameraServer::Information _information{}; bool _in_progress{}; + CameraServer::TakePhotoCallback _take_photo_callback{}; + void* _image_capture_timer_cookie{}; std::optional process_camera_information_request(const MavlinkCommandReceiver::CommandLong& command); @@ -67,8 +69,6 @@ class CameraServerImpl : public PluginImplBase { std::optional process_camera_image_capture_request(const MavlinkCommandReceiver::CommandLong& command); std::optional - process_do_trigger_control(const MavlinkCommandReceiver::CommandLong& command); - std::optional process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command); std::optional process_video_stop_capture(const MavlinkCommandReceiver::CommandLong& command); 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 d69a407dd3..259bd10975 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 @@ -56,15 +56,10 @@ class CameraServer : public PluginBase { */ ~CameraServer(); - - - - /** * @brief Type to represent a camera information. */ struct Information { - std::string vendor_name{}; /**< @brief Name of the camera vendor */ std::string model_name{}; /**< @brief Name of the camera model */ float focal_length_mm{}; /**< @brief Focal length */ @@ -79,23 +74,21 @@ class CameraServer : public PluginBase { * * @return `true` if items are equal. */ - friend bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs); + friend bool + operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs); /** * @brief Stream operator to print information about a `CameraServer::Information`. * * @return A reference to the stream. */ - friend std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information); - - - + friend std::ostream& + operator<<(std::ostream& str, CameraServer::Information const& information); /** * @brief Position type in global coordinates. */ struct Position { - double latitude_deg{}; /**< @brief Latitude in degrees (range: -90 to +90) */ double longitude_deg{}; /**< @brief Longitude in degrees (range: -180 to +180) */ float absolute_altitude_m{}; /**< @brief Altitude AMSL (above mean sea level) in metres */ @@ -116,9 +109,6 @@ class CameraServer : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, CameraServer::Position const& position); - - - /** * @brief Quaternion type. * @@ -130,7 +120,6 @@ class CameraServer : public PluginBase { * For more info see: https://en.wikipedia.org/wiki/Quaternion */ struct Quaternion { - float w{}; /**< @brief Quaternion entry 0, also denoted as a */ float x{}; /**< @brief Quaternion entry 1, also denoted as b */ float y{}; /**< @brief Quaternion entry 2, also denoted as c */ @@ -142,7 +131,8 @@ class CameraServer : public PluginBase { * * @return `true` if items are equal. */ - friend bool operator==(const CameraServer::Quaternion& lhs, const CameraServer::Quaternion& rhs); + friend bool + operator==(const CameraServer::Quaternion& lhs, const CameraServer::Quaternion& rhs); /** * @brief Stream operator to print information about a `CameraServer::Quaternion`. @@ -151,16 +141,13 @@ class CameraServer : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, CameraServer::Quaternion const& quaternion); - - - /** * @brief Information about a picture just captured. */ struct CaptureInfo { - Position position{}; /**< @brief Location where the picture was taken */ - Quaternion attitude_quaternion{}; /**< @brief Attitude of the camera when the picture was taken (quaternion) */ + Quaternion attitude_quaternion{}; /**< @brief Attitude of the camera when the picture was + taken (quaternion) */ uint64_t time_utc_us{}; /**< @brief Timestamp in UTC (since UNIX epoch) in microseconds */ bool is_success{}; /**< @brief True if the capture was successful */ int32_t index{}; /**< @brief Index from TakePhotoResponse */ @@ -172,18 +159,16 @@ class CameraServer : public PluginBase { * * @return `true` if items are equal. */ - friend bool operator==(const CameraServer::CaptureInfo& lhs, const CameraServer::CaptureInfo& rhs); + friend bool + operator==(const CameraServer::CaptureInfo& lhs, const CameraServer::CaptureInfo& rhs); /** * @brief Stream operator to print information about a `CameraServer::CaptureInfo`. * * @return A reference to the stream. */ - friend std::ostream& operator<<(std::ostream& str, CameraServer::CaptureInfo const& capture_info); - - - - + friend std::ostream& + operator<<(std::ostream& str, CameraServer::CaptureInfo const& capture_info); /** * @brief Possible results returned for action requests. @@ -207,18 +192,11 @@ class CameraServer : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, CameraServer::Result const& result); - - /** * @brief Callback type for asynchronous CameraServer calls. */ using ResultCallback = std::function; - - - - - /** * @brief Sets the camera information * @@ -228,11 +206,6 @@ class CameraServer : public PluginBase { */ Result set_information(Information information) const; - - - - - /** * @brief Sets the camera capture status * @@ -242,14 +215,10 @@ class CameraServer : public PluginBase { */ Result set_in_progress(bool in_progress) const; - - - - /** - * @brief Callback type for subscribe_take_photo. - */ - + * @brief Callback type for subscribe_take_photo. + */ + using TakePhotoCallback = std::function; /** @@ -257,24 +226,14 @@ class CameraServer : public PluginBase { */ void subscribe_take_photo(TakePhotoCallback callback); - - - - - - - /** - * @brief Adds a photo to the list of available photos + * @brief Respond to a single-image capture command. * * This function is blocking. * * @return Result of request. */ - Result publish_photo(CaptureInfo capture_info) const; - - - + Result respond_take_photo(CaptureInfo capture_info) 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 6b5cbf4fda..5c6bedd032 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 @@ -27,7 +27,7 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/SetInformation", "/mavsdk.rpc.camera_server.CameraServerService/SetInProgress", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", - "/mavsdk.rpc.camera_server.CameraServerService/PublishPhoto", + "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -40,7 +40,7 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> : channel_(channel), rpcmethod_SetInformation_(CameraServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SetInProgress_(CameraServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeTakePhoto_(CameraServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_PublishPhoto_(CameraServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_RespondTakePhoto_(CameraServerService_method_names[3], 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) { @@ -105,25 +105,25 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* Cam return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::TakePhotoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeTakePhoto_, context, request, false, nullptr); } -::grpc::Status CameraServerService::Stub::PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_PublishPhoto_, context, request, response); +::grpc::Status CameraServerService::Stub::RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondTakePhoto_, context, request, response); } -void CameraServerService::Stub::async::PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_PublishPhoto_, context, request, response, std::move(f)); +void CameraServerService::Stub::async::RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondTakePhoto_, context, request, response, std::move(f)); } -void CameraServerService::Stub::async::PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_PublishPhoto_, context, request, response, reactor); +void CameraServerService::Stub::async::RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondTakePhoto_, context, request, response, reactor); } -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* CameraServerService::Stub::PrepareAsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::PublishPhotoResponse, ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_PublishPhoto_, context, request); +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* CameraServerService::Stub::PrepareAsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse, ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondTakePhoto_, context, request); } -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* CameraServerService::Stub::AsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* CameraServerService::Stub::AsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { auto* result = - this->PrepareAsyncPublishPhotoRaw(context, request, cq); + this->PrepareAsyncRespondTakePhotoRaw(context, request, cq); result->StartCall(); return result; } @@ -162,12 +162,12 @@ CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[3], ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::camera_server::PublishPhotoRequest* req, - ::mavsdk::rpc::camera_server::PublishPhotoResponse* resp) { - return service->PublishPhoto(ctx, req, resp); + const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* req, + ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* resp) { + return service->RespondTakePhoto(ctx, req, resp); }, this))); } @@ -195,7 +195,7 @@ ::grpc::Status CameraServerService::Service::SubscribeTakePhoto(::grpc::ServerCo return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraServerService::Service::PublishPhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) { +::grpc::Status CameraServerService::Service::RespondTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response) { (void) context; (void) request; (void) response; diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index 24909863fe..a6cbce2438 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 @@ -64,13 +64,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>> PrepareAsyncSubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(PrepareAsyncSubscribeTakePhotoRaw(context, request, cq)); } - // Adds a photo to the list of available photos - virtual ::grpc::Status PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>> AsyncPublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>>(AsyncPublishPhotoRaw(context, request, cq)); + // Respond to a single-image capture command. + virtual ::grpc::Status RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> AsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(AsyncRespondTakePhotoRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>> PrepareAsyncPublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>>(PrepareAsyncPublishPhotoRaw(context, request, cq)); + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> PrepareAsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(PrepareAsyncRespondTakePhotoRaw(context, request, cq)); } class async_interface { public: @@ -83,9 +83,9 @@ class CameraServerService final { virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // Subscribe to single-image capture commands virtual void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) = 0; - // Adds a photo to the list of available photos - virtual void PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, std::function) = 0; - virtual void PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Respond to a single-image capture command. + virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) = 0; + virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -98,8 +98,8 @@ class CameraServerService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* AsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* AsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* PrepareAsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* AsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* PrepareAsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -127,12 +127,12 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>> PrepareAsyncSubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(PrepareAsyncSubscribeTakePhotoRaw(context, request, cq)); } - ::grpc::Status PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>> AsyncPublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>>(AsyncPublishPhotoRaw(context, request, cq)); + ::grpc::Status RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> AsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(AsyncRespondTakePhotoRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>> PrepareAsyncPublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>>(PrepareAsyncPublishPhotoRaw(context, request, cq)); + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> PrepareAsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(PrepareAsyncRespondTakePhotoRaw(context, request, cq)); } class async final : public StubInterface::async_interface { @@ -142,8 +142,8 @@ class CameraServerService final { void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) override; void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) override; - void PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, std::function) override; - void PublishPhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) override; + void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -162,12 +162,12 @@ class CameraServerService final { ::grpc::ClientReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* AsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* AsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* PrepareAsyncPublishPhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* AsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* PrepareAsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; - const ::grpc::internal::RpcMethod rpcmethod_PublishPhoto_; + const ::grpc::internal::RpcMethod rpcmethod_RespondTakePhoto_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -181,8 +181,8 @@ class CameraServerService final { virtual ::grpc::Status SetInProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response); // Subscribe to single-image capture commands virtual ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer); - // Adds a photo to the list of available photos - virtual ::grpc::Status PublishPhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response); + // Respond to a single-image capture command. + virtual ::grpc::Status RespondTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -245,26 +245,26 @@ class CameraServerService final { } }; template - class WithAsyncMethod_PublishPhoto : public BaseClass { + class WithAsyncMethod_RespondTakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithAsyncMethod_PublishPhoto() { + WithAsyncMethod_RespondTakePhoto() { ::grpc::Service::MarkMethodAsync(3); } - ~WithAsyncMethod_PublishPhoto() override { + ~WithAsyncMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + ::grpc::Status RespondTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestPublishPhoto(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::PublishPhotoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + void RequestRespondTakePhoto(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > AsyncService; + typedef WithAsyncMethod_SetInformation > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -342,33 +342,33 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* /*request*/) { return nullptr; } }; template - class WithCallbackMethod_PublishPhoto : public BaseClass { + class WithCallbackMethod_RespondTakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithCallbackMethod_PublishPhoto() { + WithCallbackMethod_RespondTakePhoto() { ::grpc::Service::MarkMethodCallback(3, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>( + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>( [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* request, ::mavsdk::rpc::camera_server::PublishPhotoResponse* response) { return this->PublishPhoto(context, request, response); }));} - void SetMessageAllocatorFor_PublishPhoto( - ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>* allocator) { + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response) { return this->RespondTakePhoto(context, request, response); }));} + void SetMessageAllocatorFor_RespondTakePhoto( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* allocator) { ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>*>(handler) + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>*>(handler) ->SetMessageAllocator(allocator); } - ~WithCallbackMethod_PublishPhoto() override { + ~WithCallbackMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + ::grpc::Status RespondTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* PublishPhoto( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) { return nullptr; } + virtual ::grpc::ServerUnaryReactor* RespondTakePhoto( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > CallbackService; + typedef WithCallbackMethod_SetInformation > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -422,18 +422,18 @@ class CameraServerService final { } }; template - class WithGenericMethod_PublishPhoto : public BaseClass { + class WithGenericMethod_RespondTakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_PublishPhoto() { + WithGenericMethod_RespondTakePhoto() { ::grpc::Service::MarkMethodGeneric(3); } - ~WithGenericMethod_PublishPhoto() override { + ~WithGenericMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + ::grpc::Status RespondTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } @@ -499,22 +499,22 @@ class CameraServerService final { } }; template - class WithRawMethod_PublishPhoto : public BaseClass { + class WithRawMethod_RespondTakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_PublishPhoto() { + WithRawMethod_RespondTakePhoto() { ::grpc::Service::MarkMethodRaw(3); } - ~WithRawMethod_PublishPhoto() override { + ~WithRawMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + ::grpc::Status RespondTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestPublishPhoto(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + void RequestRespondTakePhoto(::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(3, context, request, response, new_call_cq, notification_cq, tag); } }; @@ -585,25 +585,25 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template - class WithRawCallbackMethod_PublishPhoto : public BaseClass { + class WithRawCallbackMethod_RespondTakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_PublishPhoto() { + WithRawCallbackMethod_RespondTakePhoto() { ::grpc::Service::MarkMethodRawCallback(3, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->PublishPhoto(context, request, response); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondTakePhoto(context, request, response); })); } - ~WithRawCallbackMethod_PublishPhoto() override { + ~WithRawCallbackMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + ::grpc::Status RespondTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* PublishPhoto( + virtual ::grpc::ServerUnaryReactor* RespondTakePhoto( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template @@ -661,33 +661,33 @@ class CameraServerService final { virtual ::grpc::Status StreamedSetInProgress(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::SetInProgressRequest,::mavsdk::rpc::camera_server::SetInProgressResponse>* server_unary_streamer) = 0; }; template - class WithStreamedUnaryMethod_PublishPhoto : public BaseClass { + class WithStreamedUnaryMethod_RespondTakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithStreamedUnaryMethod_PublishPhoto() { + WithStreamedUnaryMethod_RespondTakePhoto() { ::grpc::Service::MarkMethodStreamed(3, new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>( + ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>( [this](::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::camera_server::PublishPhotoRequest, ::mavsdk::rpc::camera_server::PublishPhotoResponse>* streamer) { - return this->StreamedPublishPhoto(context, + ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* streamer) { + return this->StreamedRespondTakePhoto(context, streamer); })); } - ~WithStreamedUnaryMethod_PublishPhoto() override { + ~WithStreamedUnaryMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); } // disable regular version of this method - ::grpc::Status PublishPhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::PublishPhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::PublishPhotoResponse* /*response*/) override { + ::grpc::Status RespondTakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } // replace default version of method with streamed unary - virtual ::grpc::Status StreamedPublishPhoto(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::PublishPhotoRequest,::mavsdk::rpc::camera_server::PublishPhotoResponse>* server_unary_streamer) = 0; + virtual ::grpc::Status StreamedRespondTakePhoto(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest,::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_SetInformation > > StreamedUnaryService; + typedef WithStreamedUnaryMethod_SetInformation > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeTakePhoto : public BaseClass { private: @@ -716,7 +716,7 @@ class CameraServerService final { virtual ::grpc::Status StreamedSubscribeTakePhoto(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest,::mavsdk::rpc::camera_server::TakePhotoResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeTakePhoto SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > StreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 82c9875186..5cb1accb83 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 @@ -91,30 +91,30 @@ struct TakePhotoResponseDefaultTypeInternal { }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; -constexpr PublishPhotoRequest::PublishPhotoRequest( +constexpr RespondTakePhotoRequest::RespondTakePhotoRequest( ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) : capture_info_(nullptr){} -struct PublishPhotoRequestDefaultTypeInternal { - constexpr PublishPhotoRequestDefaultTypeInternal() +struct RespondTakePhotoRequestDefaultTypeInternal { + constexpr RespondTakePhotoRequestDefaultTypeInternal() : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} - ~PublishPhotoRequestDefaultTypeInternal() {} + ~RespondTakePhotoRequestDefaultTypeInternal() {} union { - PublishPhotoRequest _instance; + RespondTakePhotoRequest _instance; }; }; -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PublishPhotoRequestDefaultTypeInternal _PublishPhotoRequest_default_instance_; -constexpr PublishPhotoResponse::PublishPhotoResponse( +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT RespondTakePhotoRequestDefaultTypeInternal _RespondTakePhotoRequest_default_instance_; +constexpr RespondTakePhotoResponse::RespondTakePhotoResponse( ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) : camera_server_result_(nullptr){} -struct PublishPhotoResponseDefaultTypeInternal { - constexpr PublishPhotoResponseDefaultTypeInternal() +struct RespondTakePhotoResponseDefaultTypeInternal { + constexpr RespondTakePhotoResponseDefaultTypeInternal() : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} - ~PublishPhotoResponseDefaultTypeInternal() {} + ~RespondTakePhotoResponseDefaultTypeInternal() {} union { - PublishPhotoResponse _instance; + RespondTakePhotoResponse _instance; }; }; -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PublishPhotoResponseDefaultTypeInternal _PublishPhotoResponse_default_instance_; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT RespondTakePhotoResponseDefaultTypeInternal _RespondTakePhotoResponse_default_instance_; constexpr Information::Information( ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) : vendor_name_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) @@ -239,17 +239,17 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_camera_5fserver_2fcamera_5fser PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::TakePhotoResponse, camera_server_result_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::TakePhotoResponse, index_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::PublishPhotoRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::PublishPhotoRequest, capture_info_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, capture_info_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::PublishPhotoResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoResponse, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::PublishPhotoResponse, camera_server_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoResponse, camera_server_result_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _internal_metadata_), ~0u, // no _extensions_ @@ -306,8 +306,8 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB { 18, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, { 24, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, { 29, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, - { 36, -1, sizeof(::mavsdk::rpc::camera_server::PublishPhotoRequest)}, - { 42, -1, sizeof(::mavsdk::rpc::camera_server::PublishPhotoResponse)}, + { 36, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 42, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, { 48, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, { 60, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, { 69, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, @@ -322,8 +322,8 @@ static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = reinterpret_cast(&::mavsdk::rpc::camera_server::_SetInProgressResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::camera_server::_SubscribeTakePhotoRequest_default_instance_), reinterpret_cast(&::mavsdk::rpc::camera_server::_TakePhotoResponse_default_instance_), - reinterpret_cast(&::mavsdk::rpc::camera_server::_PublishPhotoRequest_default_instance_), - reinterpret_cast(&::mavsdk::rpc::camera_server::_PublishPhotoResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::camera_server::_Information_default_instance_), reinterpret_cast(&::mavsdk::rpc::camera_server::_Position_default_instance_), reinterpret_cast(&::mavsdk::rpc::camera_server::_Quaternion_default_instance_), @@ -345,56 +345,56 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "meraServerResult\"\033\n\031SubscribeTakePhotoRe" "quest\"n\n\021TakePhotoResponse\022J\n\024camera_ser" "ver_result\030\001 \001(\0132,.mavsdk.rpc.camera_ser" - "ver.CameraServerResult\022\r\n\005index\030\002 \001(\005\"R\n" - "\023PublishPhotoRequest\022;\n\014capture_info\030\001 \001" - "(\0132%.mavsdk.rpc.camera_server.CaptureInf" - "o\"b\n\024PublishPhotoResponse\022J\n\024camera_serv" - "er_result\030\001 \001(\0132,.mavsdk.rpc.camera_serv" - "er.CameraServerResult\"\325\001\n\013Information\022\023\n" - "\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\027" - "\n\017focal_length_mm\030\003 \001(\002\022!\n\031horizontal_se" - "nsor_size_mm\030\004 \001(\002\022\037\n\027vertical_sensor_si" - "ze_mm\030\005 \001(\002\022 \n\030horizontal_resolution_px\030" - "\006 \001(\r\022\036\n\026vertical_resolution_px\030\007 \001(\r\"q\n" - "\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongi" - "tude_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\nQuat" - "ernion\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\023attitude_quaternion\030\002 \001(\0132$.mavsdk.r" - "pc.camera_server.Quaternion\022\023\n\013time_utc_" - "us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 " - "\001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022CameraServerRe" - "sult\022C\n\006result\030\001 \001(\01623.mavsdk.rpc.camera" - "_server.CameraServerResult.Result\022\022\n\nres" - "ult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNO" - "WN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PR" - "OGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENI" - "ED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT" - "\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_" - "NO_SYSTEM\020\0102\375\003\n\023CameraServerService\022y\n\016S" - "etInformation\022/.mavsdk.rpc.camera_server" - ".SetInformationRequest\0320.mavsdk.rpc.came" - "ra_server.SetInformationResponse\"\004\200\265\030\001\022v" - "\n\rSetInProgress\022..mavsdk.rpc.camera_serv" - "er.SetInProgressRequest\032/.mavsdk.rpc.cam" - "era_server.SetInProgressResponse\"\004\200\265\030\001\022~" - "\n\022SubscribeTakePhoto\0223.mavsdk.rpc.camera" - "_server.SubscribeTakePhotoRequest\032+.mavs" - "dk.rpc.camera_server.TakePhotoResponse\"\004" - "\200\265\030\0000\001\022s\n\014PublishPhoto\022-.mavsdk.rpc.came" - "ra_server.PublishPhotoRequest\032..mavsdk.r" - "pc.camera_server.PublishPhotoResponse\"\004\200" - "\265\030\001B,\n\027io.mavsdk.camera_serverB\021CameraSe" - "rverProtob\006proto3" + "ver.CameraServerResult\022\r\n\005index\030\002 \001(\005\"V\n" + "\027RespondTakePhotoRequest\022;\n\014capture_info" + "\030\001 \001(\0132%.mavsdk.rpc.camera_server.Captur" + "eInfo\"f\n\030RespondTakePhotoResponse\022J\n\024cam" + "era_server_result\030\001 \001(\0132,.mavsdk.rpc.cam" + "era_server.CameraServerResult\"\325\001\n\013Inform" + "ation\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name" + "\030\002 \001(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031horiz" + "ontal_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_s" + "ensor_size_mm\030\005 \001(\002\022 \n\030horizontal_resolu" + "tion_px\030\006 \001(\r\022\036\n\026vertical_resolution_px\030" + "\007 \001(\r\"q\n\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022" + "\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_altit" + "ude_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\001" + "y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\0224\n\010po" + "sition\030\001 \001(\0132\".mavsdk.rpc.camera_server." + "Position\022A\n\023attitude_quaternion\030\002 \001(\0132$." + "mavsdk.rpc.camera_server.Quaternion\022\023\n\013t" + "ime_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005" + "index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022Camera" + "ServerResult\022C\n\006result\030\001 \001(\01623.mavsdk.rp" + "c.camera_server.CameraServerResult.Resul" + "t\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESU" + "LT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESU" + "LT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRES" + "ULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT" + "_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n" + "\020RESULT_NO_SYSTEM\020\0102\211\004\n\023CameraServerServ" + "ice\022y\n\016SetInformation\022/.mavsdk.rpc.camer" + "a_server.SetInformationRequest\0320.mavsdk." + "rpc.camera_server.SetInformationResponse" + "\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.cam" + "era_server.SetInProgressRequest\032/.mavsdk" + ".rpc.camera_server.SetInProgressResponse" + "\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rp" + "c.camera_server.SubscribeTakePhotoReques" + "t\032+.mavsdk.rpc.camera_server.TakePhotoRe" + "sponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mav" + "sdk.rpc.camera_server.RespondTakePhotoRe" + "quest\0322.mavsdk.rpc.camera_server.Respond" + "TakePhotoResponse\"\004\200\265\030\001B,\n\027io.mavsdk.cam" + "era_serverB\021CameraServerProtob\006proto3" ; static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, }; static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once; const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { - false, false, 2217, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", + false, false, 2237, 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, 13, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto, file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto, file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto, @@ -1615,25 +1615,25 @@ ::PROTOBUF_NAMESPACE_ID::Metadata TakePhotoResponse::GetMetadata() const { // =================================================================== -class PublishPhotoRequest::_Internal { +class RespondTakePhotoRequest::_Internal { public: - static const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info(const PublishPhotoRequest* msg); + static const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info(const RespondTakePhotoRequest* msg); }; const ::mavsdk::rpc::camera_server::CaptureInfo& -PublishPhotoRequest::_Internal::capture_info(const PublishPhotoRequest* msg) { +RespondTakePhotoRequest::_Internal::capture_info(const RespondTakePhotoRequest* msg) { return *msg->capture_info_; } -PublishPhotoRequest::PublishPhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, +RespondTakePhotoRequest::RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned) : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { SharedCtor(); if (!is_message_owned) { RegisterArenaDtor(arena); } - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.PublishPhotoRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) } -PublishPhotoRequest::PublishPhotoRequest(const PublishPhotoRequest& from) +RespondTakePhotoRequest::RespondTakePhotoRequest(const RespondTakePhotoRequest& from) : ::PROTOBUF_NAMESPACE_ID::Message() { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); if (from._internal_has_capture_info()) { @@ -1641,37 +1641,37 @@ PublishPhotoRequest::PublishPhotoRequest(const PublishPhotoRequest& from) } else { capture_info_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.PublishPhotoRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) } -inline void PublishPhotoRequest::SharedCtor() { +inline void RespondTakePhotoRequest::SharedCtor() { capture_info_ = nullptr; } -PublishPhotoRequest::~PublishPhotoRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.PublishPhotoRequest) +RespondTakePhotoRequest::~RespondTakePhotoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) if (GetArenaForAllocation() != nullptr) return; SharedDtor(); _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -inline void PublishPhotoRequest::SharedDtor() { +inline void RespondTakePhotoRequest::SharedDtor() { GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); if (this != internal_default_instance()) delete capture_info_; } -void PublishPhotoRequest::ArenaDtor(void* object) { - PublishPhotoRequest* _this = reinterpret_cast< PublishPhotoRequest* >(object); +void RespondTakePhotoRequest::ArenaDtor(void* object) { + RespondTakePhotoRequest* _this = reinterpret_cast< RespondTakePhotoRequest* >(object); (void)_this; } -void PublishPhotoRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +void RespondTakePhotoRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { } -void PublishPhotoRequest::SetCachedSize(int size) const { +void RespondTakePhotoRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -void PublishPhotoRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.PublishPhotoRequest) +void RespondTakePhotoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -1683,7 +1683,7 @@ void PublishPhotoRequest::Clear() { _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* PublishPhotoRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::PROTOBUF_NAMESPACE_ID::uint32 tag; @@ -1719,9 +1719,9 @@ const char* PublishPhotoRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAME #undef CHK_ } -::PROTOBUF_NAMESPACE_ID::uint8* PublishPhotoRequest::_InternalSerialize( +::PROTOBUF_NAMESPACE_ID::uint8* RespondTakePhotoRequest::_InternalSerialize( ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.PublishPhotoRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -1737,12 +1737,12 @@ ::PROTOBUF_NAMESPACE_ID::uint8* PublishPhotoRequest::_InternalSerialize( target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.PublishPhotoRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondTakePhotoRequest) return target; } -size_t PublishPhotoRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.PublishPhotoRequest) +size_t RespondTakePhotoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) size_t total_size = 0; ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; @@ -1765,21 +1765,21 @@ size_t PublishPhotoRequest::ByteSizeLong() const { return total_size; } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData PublishPhotoRequest::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, - PublishPhotoRequest::MergeImpl + RespondTakePhotoRequest::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*PublishPhotoRequest::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoRequest::GetClassData() const { return &_class_data_; } -void PublishPhotoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, +void RespondTakePhotoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from) { - static_cast(to)->MergeFrom( - static_cast(from)); + static_cast(to)->MergeFrom( + static_cast(from)); } -void PublishPhotoRequest::MergeFrom(const PublishPhotoRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.PublishPhotoRequest) +void RespondTakePhotoRequest::MergeFrom(const RespondTakePhotoRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) GOOGLE_DCHECK_NE(&from, this); ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -1790,24 +1790,24 @@ void PublishPhotoRequest::MergeFrom(const PublishPhotoRequest& from) { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void PublishPhotoRequest::CopyFrom(const PublishPhotoRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.PublishPhotoRequest) +void RespondTakePhotoRequest::CopyFrom(const RespondTakePhotoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool PublishPhotoRequest::IsInitialized() const { +bool RespondTakePhotoRequest::IsInitialized() const { return true; } -void PublishPhotoRequest::InternalSwap(PublishPhotoRequest* other) { +void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(capture_info_, other->capture_info_); } -::PROTOBUF_NAMESPACE_ID::Metadata PublishPhotoRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { return ::PROTOBUF_NAMESPACE_ID::internal::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[6]); @@ -1815,25 +1815,25 @@ ::PROTOBUF_NAMESPACE_ID::Metadata PublishPhotoRequest::GetMetadata() const { // =================================================================== -class PublishPhotoResponse::_Internal { +class RespondTakePhotoResponse::_Internal { public: - static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const PublishPhotoResponse* msg); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondTakePhotoResponse* msg); }; const ::mavsdk::rpc::camera_server::CameraServerResult& -PublishPhotoResponse::_Internal::camera_server_result(const PublishPhotoResponse* msg) { +RespondTakePhotoResponse::_Internal::camera_server_result(const RespondTakePhotoResponse* msg) { return *msg->camera_server_result_; } -PublishPhotoResponse::PublishPhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, +RespondTakePhotoResponse::RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned) : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { SharedCtor(); if (!is_message_owned) { RegisterArenaDtor(arena); } - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.PublishPhotoResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) } -PublishPhotoResponse::PublishPhotoResponse(const PublishPhotoResponse& from) +RespondTakePhotoResponse::RespondTakePhotoResponse(const RespondTakePhotoResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message() { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); if (from._internal_has_camera_server_result()) { @@ -1841,37 +1841,37 @@ PublishPhotoResponse::PublishPhotoResponse(const PublishPhotoResponse& from) } else { camera_server_result_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.PublishPhotoResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) } -inline void PublishPhotoResponse::SharedCtor() { +inline void RespondTakePhotoResponse::SharedCtor() { camera_server_result_ = nullptr; } -PublishPhotoResponse::~PublishPhotoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.PublishPhotoResponse) +RespondTakePhotoResponse::~RespondTakePhotoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) if (GetArenaForAllocation() != nullptr) return; SharedDtor(); _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -inline void PublishPhotoResponse::SharedDtor() { +inline void RespondTakePhotoResponse::SharedDtor() { GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); if (this != internal_default_instance()) delete camera_server_result_; } -void PublishPhotoResponse::ArenaDtor(void* object) { - PublishPhotoResponse* _this = reinterpret_cast< PublishPhotoResponse* >(object); +void RespondTakePhotoResponse::ArenaDtor(void* object) { + RespondTakePhotoResponse* _this = reinterpret_cast< RespondTakePhotoResponse* >(object); (void)_this; } -void PublishPhotoResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +void RespondTakePhotoResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { } -void PublishPhotoResponse::SetCachedSize(int size) const { +void RespondTakePhotoResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -void PublishPhotoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.PublishPhotoResponse) +void RespondTakePhotoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -1883,7 +1883,7 @@ void PublishPhotoResponse::Clear() { _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* PublishPhotoResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +const char* RespondTakePhotoResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::PROTOBUF_NAMESPACE_ID::uint32 tag; @@ -1919,9 +1919,9 @@ const char* PublishPhotoResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAM #undef CHK_ } -::PROTOBUF_NAMESPACE_ID::uint8* PublishPhotoResponse::_InternalSerialize( +::PROTOBUF_NAMESPACE_ID::uint8* RespondTakePhotoResponse::_InternalSerialize( ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.PublishPhotoResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -1937,12 +1937,12 @@ ::PROTOBUF_NAMESPACE_ID::uint8* PublishPhotoResponse::_InternalSerialize( target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.PublishPhotoResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondTakePhotoResponse) return target; } -size_t PublishPhotoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.PublishPhotoResponse) +size_t RespondTakePhotoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) size_t total_size = 0; ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; @@ -1965,21 +1965,21 @@ size_t PublishPhotoResponse::ByteSizeLong() const { return total_size; } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData PublishPhotoResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, - PublishPhotoResponse::MergeImpl + RespondTakePhotoResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*PublishPhotoResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoResponse::GetClassData() const { return &_class_data_; } -void PublishPhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, +void RespondTakePhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from) { - static_cast(to)->MergeFrom( - static_cast(from)); + static_cast(to)->MergeFrom( + static_cast(from)); } -void PublishPhotoResponse::MergeFrom(const PublishPhotoResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.PublishPhotoResponse) +void RespondTakePhotoResponse::MergeFrom(const RespondTakePhotoResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) GOOGLE_DCHECK_NE(&from, this); ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -1990,24 +1990,24 @@ void PublishPhotoResponse::MergeFrom(const PublishPhotoResponse& from) { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void PublishPhotoResponse::CopyFrom(const PublishPhotoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.PublishPhotoResponse) +void RespondTakePhotoResponse::CopyFrom(const RespondTakePhotoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool PublishPhotoResponse::IsInitialized() const { +bool RespondTakePhotoResponse::IsInitialized() const { return true; } -void PublishPhotoResponse::InternalSwap(PublishPhotoResponse* other) { +void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(camera_server_result_, other->camera_server_result_); } -::PROTOBUF_NAMESPACE_ID::Metadata PublishPhotoResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { return ::PROTOBUF_NAMESPACE_ID::internal::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[7]); @@ -3510,11 +3510,11 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeTakePhotoReq template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::TakePhotoResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::TakePhotoResponse >(arena); } -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::PublishPhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::PublishPhotoRequest >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::PublishPhotoRequest >(arena); +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); } -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::PublishPhotoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::PublishPhotoResponse >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::PublishPhotoResponse >(arena); +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse >(arena); } template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::Information* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::Information >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::Information >(arena); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index a6342988e1..6828a984e1 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 @@ -70,15 +70,15 @@ extern InformationDefaultTypeInternal _Information_default_instance_; class Position; struct PositionDefaultTypeInternal; extern PositionDefaultTypeInternal _Position_default_instance_; -class PublishPhotoRequest; -struct PublishPhotoRequestDefaultTypeInternal; -extern PublishPhotoRequestDefaultTypeInternal _PublishPhotoRequest_default_instance_; -class PublishPhotoResponse; -struct PublishPhotoResponseDefaultTypeInternal; -extern PublishPhotoResponseDefaultTypeInternal _PublishPhotoResponse_default_instance_; class Quaternion; struct QuaternionDefaultTypeInternal; extern QuaternionDefaultTypeInternal _Quaternion_default_instance_; +class RespondTakePhotoRequest; +struct RespondTakePhotoRequestDefaultTypeInternal; +extern RespondTakePhotoRequestDefaultTypeInternal _RespondTakePhotoRequest_default_instance_; +class RespondTakePhotoResponse; +struct RespondTakePhotoResponseDefaultTypeInternal; +extern RespondTakePhotoResponseDefaultTypeInternal _RespondTakePhotoResponse_default_instance_; class SetInProgressRequest; struct SetInProgressRequestDefaultTypeInternal; extern SetInProgressRequestDefaultTypeInternal _SetInProgressRequest_default_instance_; @@ -105,9 +105,9 @@ template<> ::mavsdk::rpc::camera_server::CameraServerResult* Arena::CreateMaybeM template<> ::mavsdk::rpc::camera_server::CaptureInfo* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(Arena*); template<> ::mavsdk::rpc::camera_server::Information* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(Arena*); template<> ::mavsdk::rpc::camera_server::Position* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Position>(Arena*); -template<> ::mavsdk::rpc::camera_server::PublishPhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::PublishPhotoRequest>(Arena*); -template<> ::mavsdk::rpc::camera_server::PublishPhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::PublishPhotoResponse>(Arena*); template<> ::mavsdk::rpc::camera_server::Quaternion* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Quaternion>(Arena*); +template<> ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondTakePhotoRequest>(Arena*); +template<> ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondTakePhotoResponse>(Arena*); template<> ::mavsdk::rpc::camera_server::SetInProgressRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInProgressRequest>(Arena*); template<> ::mavsdk::rpc::camera_server::SetInProgressResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInProgressResponse>(Arena*); template<> ::mavsdk::rpc::camera_server::SetInformationRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInformationRequest>(Arena*); @@ -1021,24 +1021,24 @@ class TakePhotoResponse final : }; // ------------------------------------------------------------------- -class PublishPhotoRequest final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.PublishPhotoRequest) */ { +class RespondTakePhotoRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { public: - inline PublishPhotoRequest() : PublishPhotoRequest(nullptr) {} - ~PublishPhotoRequest() override; - explicit constexpr PublishPhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} + ~RespondTakePhotoRequest() override; + explicit constexpr RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - PublishPhotoRequest(const PublishPhotoRequest& from); - PublishPhotoRequest(PublishPhotoRequest&& from) noexcept - : PublishPhotoRequest() { + RespondTakePhotoRequest(const RespondTakePhotoRequest& from); + RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept + : RespondTakePhotoRequest() { *this = ::std::move(from); } - inline PublishPhotoRequest& operator=(const PublishPhotoRequest& from) { + inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { CopyFrom(from); return *this; } - inline PublishPhotoRequest& operator=(PublishPhotoRequest&& from) noexcept { + inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena()) { InternalSwap(&from); @@ -1057,20 +1057,20 @@ class PublishPhotoRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishPhotoRequest& default_instance() { + static const RespondTakePhotoRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishPhotoRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishPhotoRequest_default_instance_); + static inline const RespondTakePhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = 6; - friend void swap(PublishPhotoRequest& a, PublishPhotoRequest& b) { + friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { a.Swap(&b); } - inline void Swap(PublishPhotoRequest* other) { + inline void Swap(RespondTakePhotoRequest* other) { if (other == this) return; if (GetOwningArena() == other->GetOwningArena()) { InternalSwap(other); @@ -1078,7 +1078,7 @@ class PublishPhotoRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishPhotoRequest* other) { + void UnsafeArenaSwap(RespondTakePhotoRequest* other) { if (other == this) return; GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -1086,17 +1086,17 @@ class PublishPhotoRequest final : // implements Message ---------------------------------------------- - inline PublishPhotoRequest* New() const final { - return new PublishPhotoRequest(); + inline RespondTakePhotoRequest* New() const final { + return new RespondTakePhotoRequest(); } - PublishPhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { - return CreateMaybeMessage(arena); + RespondTakePhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const PublishPhotoRequest& from); + void CopyFrom(const RespondTakePhotoRequest& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom(const PublishPhotoRequest& from); + void MergeFrom(const RespondTakePhotoRequest& from); private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); public: @@ -1113,13 +1113,13 @@ class PublishPhotoRequest final : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(PublishPhotoRequest* other); + void InternalSwap(RespondTakePhotoRequest* other); friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { - return "mavsdk.rpc.camera_server.PublishPhotoRequest"; + return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; } protected: - explicit PublishPhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + explicit RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned = false); private: static void ArenaDtor(void* object); @@ -1156,7 +1156,7 @@ class PublishPhotoRequest final : ::mavsdk::rpc::camera_server::CaptureInfo* capture_info); ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.PublishPhotoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoRequest) private: class _Internal; @@ -1169,24 +1169,24 @@ class PublishPhotoRequest final : }; // ------------------------------------------------------------------- -class PublishPhotoResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.PublishPhotoResponse) */ { +class RespondTakePhotoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { public: - inline PublishPhotoResponse() : PublishPhotoResponse(nullptr) {} - ~PublishPhotoResponse() override; - explicit constexpr PublishPhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} + ~RespondTakePhotoResponse() override; + explicit constexpr RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - PublishPhotoResponse(const PublishPhotoResponse& from); - PublishPhotoResponse(PublishPhotoResponse&& from) noexcept - : PublishPhotoResponse() { + RespondTakePhotoResponse(const RespondTakePhotoResponse& from); + RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept + : RespondTakePhotoResponse() { *this = ::std::move(from); } - inline PublishPhotoResponse& operator=(const PublishPhotoResponse& from) { + inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { CopyFrom(from); return *this; } - inline PublishPhotoResponse& operator=(PublishPhotoResponse&& from) noexcept { + inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena()) { InternalSwap(&from); @@ -1205,20 +1205,20 @@ class PublishPhotoResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishPhotoResponse& default_instance() { + static const RespondTakePhotoResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishPhotoResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishPhotoResponse_default_instance_); + static inline const RespondTakePhotoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = 7; - friend void swap(PublishPhotoResponse& a, PublishPhotoResponse& b) { + friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { a.Swap(&b); } - inline void Swap(PublishPhotoResponse* other) { + inline void Swap(RespondTakePhotoResponse* other) { if (other == this) return; if (GetOwningArena() == other->GetOwningArena()) { InternalSwap(other); @@ -1226,7 +1226,7 @@ class PublishPhotoResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishPhotoResponse* other) { + void UnsafeArenaSwap(RespondTakePhotoResponse* other) { if (other == this) return; GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -1234,17 +1234,17 @@ class PublishPhotoResponse final : // implements Message ---------------------------------------------- - inline PublishPhotoResponse* New() const final { - return new PublishPhotoResponse(); + inline RespondTakePhotoResponse* New() const final { + return new RespondTakePhotoResponse(); } - PublishPhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { - return CreateMaybeMessage(arena); + RespondTakePhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const PublishPhotoResponse& from); + void CopyFrom(const RespondTakePhotoResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom(const PublishPhotoResponse& from); + void MergeFrom(const RespondTakePhotoResponse& from); private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); public: @@ -1261,13 +1261,13 @@ class PublishPhotoResponse final : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(PublishPhotoResponse* other); + void InternalSwap(RespondTakePhotoResponse* other); friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { - return "mavsdk.rpc.camera_server.PublishPhotoResponse"; + return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; } protected: - explicit PublishPhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + explicit RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned = false); private: static void ArenaDtor(void* object); @@ -1304,7 +1304,7 @@ class PublishPhotoResponse final : ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.PublishPhotoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoResponse) private: class _Internal; @@ -2723,31 +2723,31 @@ inline void TakePhotoResponse::set_index(::PROTOBUF_NAMESPACE_ID::int32 value) { // ------------------------------------------------------------------- -// PublishPhotoRequest +// RespondTakePhotoRequest // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 1; -inline bool PublishPhotoRequest::_internal_has_capture_info() const { +inline bool RespondTakePhotoRequest::_internal_has_capture_info() const { return this != internal_default_instance() && capture_info_ != nullptr; } -inline bool PublishPhotoRequest::has_capture_info() const { +inline bool RespondTakePhotoRequest::has_capture_info() const { return _internal_has_capture_info(); } -inline void PublishPhotoRequest::clear_capture_info() { +inline void RespondTakePhotoRequest::clear_capture_info() { if (GetArenaForAllocation() == nullptr && capture_info_ != nullptr) { delete capture_info_; } capture_info_ = nullptr; } -inline const ::mavsdk::rpc::camera_server::CaptureInfo& PublishPhotoRequest::_internal_capture_info() const { +inline const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::_internal_capture_info() const { const ::mavsdk::rpc::camera_server::CaptureInfo* p = capture_info_; return p != nullptr ? *p : reinterpret_cast( ::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_); } -inline const ::mavsdk::rpc::camera_server::CaptureInfo& PublishPhotoRequest::capture_info() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) +inline const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::capture_info() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) return _internal_capture_info(); } -inline void PublishPhotoRequest::unsafe_arena_set_allocated_capture_info( +inline void RespondTakePhotoRequest::unsafe_arena_set_allocated_capture_info( ::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { if (GetArenaForAllocation() == nullptr) { delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(capture_info_); @@ -2758,9 +2758,9 @@ inline void PublishPhotoRequest::unsafe_arena_set_allocated_capture_info( } else { } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) } -inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::release_capture_info() { +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::release_capture_info() { ::mavsdk::rpc::camera_server::CaptureInfo* temp = capture_info_; capture_info_ = nullptr; @@ -2775,14 +2775,14 @@ inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::release_c #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return temp; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::unsafe_arena_release_capture_info() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::unsafe_arena_release_capture_info() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) ::mavsdk::rpc::camera_server::CaptureInfo* temp = capture_info_; capture_info_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::_internal_mutable_capture_info() { +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::_internal_mutable_capture_info() { if (capture_info_ == nullptr) { auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(GetArenaForAllocation()); @@ -2790,12 +2790,12 @@ inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::_internal } return capture_info_; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* PublishPhotoRequest::mutable_capture_info() { +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::mutable_capture_info() { ::mavsdk::rpc::camera_server::CaptureInfo* _msg = _internal_mutable_capture_info(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) return _msg; } -inline void PublishPhotoRequest::set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { +inline void RespondTakePhotoRequest::set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); if (message_arena == nullptr) { delete capture_info_; @@ -2812,36 +2812,36 @@ inline void PublishPhotoRequest::set_allocated_capture_info(::mavsdk::rpc::camer } capture_info_ = capture_info; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.PublishPhotoRequest.capture_info) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) } // ------------------------------------------------------------------- -// PublishPhotoResponse +// RespondTakePhotoResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool PublishPhotoResponse::_internal_has_camera_server_result() const { +inline bool RespondTakePhotoResponse::_internal_has_camera_server_result() const { return this != internal_default_instance() && camera_server_result_ != nullptr; } -inline bool PublishPhotoResponse::has_camera_server_result() const { +inline bool RespondTakePhotoResponse::has_camera_server_result() const { return _internal_has_camera_server_result(); } -inline void PublishPhotoResponse::clear_camera_server_result() { +inline void RespondTakePhotoResponse::clear_camera_server_result() { if (GetArenaForAllocation() == nullptr && camera_server_result_ != nullptr) { delete camera_server_result_; } camera_server_result_ = nullptr; } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& PublishPhotoResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondTakePhotoResponse::_internal_camera_server_result() const { const ::mavsdk::rpc::camera_server::CameraServerResult* p = camera_server_result_; return p != nullptr ? *p : reinterpret_cast( ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& PublishPhotoResponse::camera_server_result() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondTakePhotoResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) return _internal_camera_server_result(); } -inline void PublishPhotoResponse::unsafe_arena_set_allocated_camera_server_result( +inline void RespondTakePhotoResponse::unsafe_arena_set_allocated_camera_server_result( ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { if (GetArenaForAllocation() == nullptr) { delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(camera_server_result_); @@ -2852,9 +2852,9 @@ inline void PublishPhotoResponse::unsafe_arena_set_allocated_camera_server_resul } else { } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.PublishPhotoResponse.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* PublishPhotoResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::release_camera_server_result() { ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; camera_server_result_ = nullptr; @@ -2869,14 +2869,14 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::r #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::unsafe_arena_release_camera_server_result() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) ::mavsdk::rpc::camera_server::CameraServerResult* temp = camera_server_result_; camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::_internal_mutable_camera_server_result() { if (camera_server_result_ == nullptr) { auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); @@ -2884,12 +2884,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::_ } return camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* PublishPhotoResponse::mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::mutable_camera_server_result() { ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) return _msg; } -inline void PublishPhotoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { +inline void RespondTakePhotoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); if (message_arena == nullptr) { delete camera_server_result_; @@ -2906,7 +2906,7 @@ inline void PublishPhotoResponse::set_allocated_camera_server_result(::mavsdk::r } camera_server_result_ = camera_server_result; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.PublishPhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoResponse.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 2308e1ba6f..427d58a0e4 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 @@ -354,10 +354,10 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } - grpc::Status PublishPhoto( + grpc::Status RespondTakePhoto( grpc::ServerContext* /* context */, - const rpc::camera_server::PublishPhotoRequest* request, - rpc::camera_server::PublishPhotoResponse* response) override + const rpc::camera_server::RespondTakePhotoRequest* request, + rpc::camera_server::RespondTakePhotoResponse* response) override { if (_lazy_plugin.maybe_plugin() == nullptr) { if (response != nullptr) { @@ -369,11 +369,11 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer } if (request == nullptr) { - LogWarn() << "PublishPhoto sent with a null request! Ignoring..."; + LogWarn() << "RespondTakePhoto sent with a null request! Ignoring..."; return grpc::Status::OK; } - auto result = _lazy_plugin.maybe_plugin()->publish_photo( + auto result = _lazy_plugin.maybe_plugin()->respond_take_photo( translateFromRpcCaptureInfo(request->capture_info())); if (response != nullptr) { From b5ea0d6e959f354d9a6d3945115ce246b5e80649 Mon Sep 17 00:00:00 2001 From: David Lechner Date: Tue, 15 Feb 2022 14:30:20 -0600 Subject: [PATCH 3/6] camera_server: improvements and fixes example: - fix more than one new system in subscribe_on_new_system() callback - fix use after free - publish photo to all systems plugin: - fix take photo logic - add support for interval flag in capture status message - add support for image count in capture status message --- examples/camera_server/camera_server.cpp | 136 ++++++++--------- .../camera_server/camera_server_impl.cpp | 144 +++++++++++++----- .../camera_server/camera_server_impl.h | 14 +- 3 files changed, 187 insertions(+), 107 deletions(-) diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index b25c22282d..20953fc6ec 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -27,68 +27,6 @@ using std::chrono::milliseconds; using std::chrono::system_clock; using std::this_thread::sleep_for; -// map of system id to camera server instance -static std::map> all_camera_servers{}; - -void handle_per_system_camera(std::shared_ptr system) -{ - if (all_camera_servers.find(system->get_system_id()) != all_camera_servers.end()) { - std::cerr << "Unexpected duplicate system ID " << +system->get_system_id() << ", ignoring." - << std::endl; - return; - } - - // Create server plugin - auto camera_server = std::make_shared(system); - - all_camera_servers.insert({system->get_system_id(), camera_server}); - - camera_server->set_information({ - .vendor_name = "MAVSDK", - .model_name = "Example Camera Server", - .focal_length_mm = 3.0, - .horizontal_sensor_size_mm = 3.68, - .vertical_sensor_size_mm = 2.76, - .horizontal_resolution_px = 3280, - .vertical_resolution_px = 2464, - }); - - camera_server->set_in_progress(false); - - camera_server->subscribe_take_photo( - [camera_server](CameraServer::Result result, int32_t index) { - camera_server->set_in_progress(true); - - std::cout << "taking a picture..." << std::endl; - - // TODO : actually capture image here - // simulating with delay - sleep_for(seconds(1)); - - // TODO: populate with telemetry data - auto position = CameraServer::Position{}; - auto attitude = CameraServer::Quaternion{}; - - auto timestamp = - duration_cast(system_clock::now().time_since_epoch()).count(); - auto success = true; - - camera_server->set_in_progress(false); - - camera_server->respond_take_photo({ - .position = position, - .attitude_quaternion = attitude, - .time_utc_us = static_cast(timestamp), - .is_success = success, - .index = index, - .file_url = {}, - }); - }); - - std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") << " system ID " - << +system->get_system_id() << std::endl; -} - int main(int argc, char** argv) { mavsdk::Mavsdk mavsdk; @@ -101,17 +39,73 @@ int main(int argc, char** argv) std::cout << "Created camera server connection" << std::endl; } - mavsdk.subscribe_on_new_system([&mavsdk]() { - // REVISIT: is it safe to assume that this will not miss any systems, - // e.g. two discovered at the same time? - auto system = mavsdk.systems().back(); + // map of system id to camera server instance + std::map> all_camera_servers{}; + + auto attach_camera_server = [&]() { + for (auto&& system : mavsdk.systems()) { + // if we have already created a camera server for this system, skip it + if (all_camera_servers.find(system->get_system_id()) != all_camera_servers.end()) { + continue; + } + + // Create server plugin + auto camera_server = std::make_shared(system); + + all_camera_servers.insert({system->get_system_id(), camera_server}); + + camera_server->set_information({ + .vendor_name = "MAVSDK", + .model_name = "Example Camera Server", + .focal_length_mm = 3.0, + .horizontal_sensor_size_mm = 3.68, + .vertical_sensor_size_mm = 2.76, + .horizontal_resolution_px = 3280, + .vertical_resolution_px = 2464, + }); - handle_per_system_camera(system); - }); + camera_server->set_in_progress(false); - for (auto&& system : mavsdk.systems()) { - handle_per_system_camera(system); - } + camera_server->subscribe_take_photo( + [camera_server, &all_camera_servers](CameraServer::Result result, int32_t index) { + camera_server->set_in_progress(true); + + std::cout << "taking a picture (" << +index << ")..." << std::endl; + + // TODO : actually capture image here + // simulating with delay + sleep_for(milliseconds(500)); + + // TODO: populate with telemetry data + auto position = CameraServer::Position{}; + auto attitude = CameraServer::Quaternion{}; + + auto timestamp = + duration_cast(system_clock::now().time_since_epoch()).count(); + auto success = true; + + camera_server->set_in_progress(false); + + // hack to simulate broadcast and keep total count in sync + for (auto&& [key, value] : all_camera_servers) { + value->respond_take_photo({ + .position = position, + .attitude_quaternion = attitude, + .time_utc_us = static_cast(timestamp), + .is_success = success, + .index = index, + .file_url = {}, + }); + } + }); + + std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") + << " system ID " << +system->get_system_id() << std::endl; + } + }; + + mavsdk.subscribe_on_new_system(attach_camera_server); + attach_camera_server(); while (true) { // TODO: better way to wait forever? diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 08253eac53..2ed47fdf78 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -140,7 +140,10 @@ void CameraServerImpl::deinit() {} void CameraServerImpl::enable() {} -void CameraServerImpl::disable() {} +void CameraServerImpl::disable() +{ + stop_image_capture_interval(); +} CameraServer::Result CameraServerImpl::set_information(CameraServer::Information information) { @@ -151,7 +154,7 @@ CameraServer::Result CameraServerImpl::set_information(CameraServer::Information CameraServer::Result CameraServerImpl::set_in_progress(bool in_progress) { - _in_progress = in_progress; + _is_image_capture_in_progress = in_progress; return CameraServer::Result::Success; } @@ -162,9 +165,27 @@ void CameraServerImpl::subscribe_take_photo(CameraServer::TakePhotoCallback call CameraServer::Result CameraServerImpl::respond_take_photo(CameraServer::CaptureInfo capture_info) { + // If capture_info.index == INT32_MIN, it means this was an interval + // capture rather than a single image capture. + if (capture_info.index != INT32_MIN) { + // We expect each capture to be the next sequential number. + // If _image_capture_count == 0, we ignore since it means that this is + // the first photo since the plugin was intialized. + if (_image_capture_count != 0 && capture_info.index != _image_capture_count + 1) { + LogErr() << "unexpected image index, expecting " << +(_image_capture_count + 1) + << " but was " << +capture_info.index; + } + + _image_capture_count = capture_info.index; + } + + // REVISIT: Should we cache all CaptureInfo in memory for single image + // captures so that we can respond to requests for lost CAMERA_IMAGE_CAPTURED + // messages without calling back to user code? + static const uint8_t camera_id = 0; // deprecated unused field - const float attitude_quaternion[] = { + const float attitude_quaternion[] = { capture_info.attitude_quaternion.w, capture_info.attitude_quaternion.x, capture_info.attitude_quaternion.y, @@ -188,12 +209,59 @@ CameraServer::Result CameraServerImpl::respond_take_photo(CameraServer::CaptureI capture_info.is_success, capture_info.file_url.c_str()); + // TODO: this should be a broadcast message _parent->send_message(msg); LogDebug() << "sent camera image captured msg - index: " << +capture_info.index; return CameraServer::Result::Success; } +/** + * Starts capturing images with the given interval. + * @param [in] interval_s The interval between captures in seconds. + * @param [in] count The number of images to capture or 0 for "forever". + * @param [in] index The index/sequence number pass to the user callback (always + * @c INT32_MIN). + */ +void CameraServerImpl::start_image_capture_interval(float interval_s, int32_t count, int32_t index) +{ + // If count == 0, it means capture "forever" until a stop command is received. + auto remaining = std::make_shared(count == 0 ? INT32_MAX : count); + + _parent->add_call_every( + [this, remaining, index]() { + LogDebug() << "capture image timer triggered"; + + if (_take_photo_callback) { + _take_photo_callback(CameraServer::Result::Success, index); + (*remaining)--; + } + + if (*remaining == 0) { + stop_image_capture_interval(); + } + }, + interval_s, + &_image_capture_timer_cookie); + + _is_image_capture_interval_set = true; + _image_capture_timer_interval_s = interval_s; +} + +/** + * Stops any pending image capture interval timer. + */ +void CameraServerImpl::stop_image_capture_interval() +{ + if (_image_capture_timer_cookie) { + _parent->remove_call_every(_image_capture_timer_cookie); + } + + _image_capture_timer_cookie = nullptr; + _is_image_capture_interval_set = false; + _image_capture_timer_interval_s = 0; +} + std::optional CameraServerImpl::process_camera_information_request( const MavlinkCommandReceiver::CommandLong& command) { @@ -378,15 +446,17 @@ std::optional CameraServerImpl::process_camera_capture_status std::this_thread::sleep_for(std::chrono::milliseconds(100)); uint8_t image_status{}; - if (_in_progress) { + + if (_is_image_capture_in_progress) { image_status |= StatusFlags::IN_PROGRESS; } - int32_t image_count = 0; // TODO: get image capture vector length + if (_is_image_capture_interval_set) { + image_status |= StatusFlags::INTERVAL_SET; + } // unsupported const uint8_t video_status = 0; - const float image_interval = 0; const uint32_t recording_time_ms = 0; const float available_capacity = 0; @@ -398,10 +468,10 @@ std::optional CameraServerImpl::process_camera_capture_status static_cast(_parent->get_time().elapsed_s() * 1e3), image_status, video_status, - image_interval, + _image_capture_timer_interval_s, recording_time_ms, available_capacity, - image_count); + _image_capture_count); _parent->send_message(msg); @@ -478,36 +548,43 @@ CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::Comman std::optional CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command) { - auto interval = command.params.param2; - auto total_images = static_cast(command.params.param3); - auto seq_number = static_cast(command.params.param4); - - auto current = std::make_shared(total_images == 1 ? seq_number : 1); - auto end = *current + total_images; - auto forever = total_images == 0; + auto interval_s = command.params.param2; + auto total_images = static_cast(command.params.param3); + auto seq_number = static_cast(command.params.param4); - LogDebug() << "received image start capture request - interval: " << +interval << " total: " << +total_images << " index: " << +seq_number; + LogDebug() << "received image start capture request - interval: " << +interval_s + << " total: " << +total_images << " index: " << +seq_number; // TODO: validate parameters and return MAV_RESULT_DENIED not valid - // cancel any previous handler - if (_image_capture_timer_cookie) { - _parent->unregister_timeout_handler(_image_capture_timer_cookie); - _image_capture_timer_cookie = nullptr; - } + stop_image_capture_interval(); - _parent->register_timeout_handler([this, current, end, forever]() { - LogDebug() << "capture image timer triggered"; + if (!_take_photo_callback) { + LogDebug() << "image capture requested with no take photo subscriber"; + return _parent->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED); + } - if (_take_photo_callback) { - _take_photo_callback(CameraServer::Result::Success, *current); + // single image capture + if (total_images == 1) { + if (seq_number <= _image_capture_count) { + LogDebug() << "received duplicate single image capture request"; + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_DENIED); } - if (!forever && ++(*current) >= end) { - _parent->unregister_timeout_handler(_image_capture_timer_cookie); - _image_capture_timer_cookie = nullptr; - } - }, interval, &_image_capture_timer_cookie); + // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED + auto ack_msg = _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + _parent->send_message(ack_msg); + + // FIXME: why is this needed to prevent dropping messages? + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + _take_photo_callback(CameraServer::Result::Success, seq_number); + + return std::nullopt; + } + + start_image_capture_interval(interval_s, total_images, seq_number); return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); } @@ -517,10 +594,9 @@ CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::Comma { LogDebug() << "received image stop capture request"; - if (_image_capture_timer_cookie) { - _parent->unregister_timeout_handler(_image_capture_timer_cookie); - _image_capture_timer_cookie = nullptr; - } + // REVISIT: should we returns something other that MAV_RESULT_ACCEPTED if + // there is not currently a capture interval active? + stop_image_capture_interval(); return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); } diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 9a180e44e1..3c72cc7ef5 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -38,9 +38,19 @@ class CameraServerImpl : public PluginImplBase { bool _is_information_set{}; CameraServer::Information _information{}; - bool _in_progress{}; - CameraServer::TakePhotoCallback _take_photo_callback{}; + + // 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{}; + + CameraServer::TakePhotoCallback _take_photo_callback{}; + + void start_image_capture_interval(float interval, int32_t count, int32_t index); + void stop_image_capture_interval(); std::optional process_camera_information_request(const MavlinkCommandReceiver::CommandLong& command); From 6c17373cc3f9a7f8a356b8088a865949892fc46c Mon Sep 17 00:00:00 2001 From: David Lechner Date: Thu, 17 Feb 2022 11:53:54 -0600 Subject: [PATCH 4/6] camera_server: use subscriptions as capability flags --- examples/camera_server/camera_server.cpp | 40 ++++++++----------- proto | 2 +- .../camera_server/camera_server_impl.cpp | 12 ++++-- 3 files changed, 27 insertions(+), 27 deletions(-) diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 20953fc6ec..c65e624376 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -7,18 +7,6 @@ #include #include -/* - This example runs a MAVLink "camera" utilizing the MAVSDK server plugins - on a separate thread. This uses two MAVSDK instances, one GCS, one camera. - - The main thread acts as a GCS and reads telemetry, parameters, transmits across - a mission, clears the mission, arms the vehicle and then triggers a vehicle takeoff. - - The camera thread handles all the servers and triggers callbacks, publishes telemetry, - handles and stores parameters, prints received missions and sets the vehicle height to 10m on - successful takeoff request. -*/ - using namespace mavsdk; using std::chrono::duration_cast; @@ -54,17 +42,7 @@ int main(int argc, char** argv) all_camera_servers.insert({system->get_system_id(), camera_server}); - camera_server->set_information({ - .vendor_name = "MAVSDK", - .model_name = "Example Camera Server", - .focal_length_mm = 3.0, - .horizontal_sensor_size_mm = 3.68, - .vertical_sensor_size_mm = 2.76, - .horizontal_resolution_px = 3280, - .vertical_resolution_px = 2464, - }); - - camera_server->set_in_progress(false); + // First add all subscriptions. This defines the camera capabilities. camera_server->subscribe_take_photo( [camera_server, &all_camera_servers](CameraServer::Result result, int32_t index) { @@ -99,6 +77,22 @@ int main(int argc, char** argv) } }); + // Then set the initial state of everything. + + camera_server->set_in_progress(false); + + // Finally call set_information() to "activate" the camera plugin. + + camera_server->set_information({ + .vendor_name = "MAVSDK", + .model_name = "Example Camera Server", + .focal_length_mm = 3.0, + .horizontal_sensor_size_mm = 3.68, + .vertical_sensor_size_mm = 2.76, + .horizontal_resolution_px = 3280, + .vertical_resolution_px = 2464, + }); + std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") << " system ID " << +system->get_system_id() << std::endl; } diff --git a/proto b/proto index 57f5e7f9d3..4b3f0573dd 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 57f5e7f9d3d116fca49b570f2074f3defefcd8aa +Subproject commit 4b3f0573dddaf1de7efcc1efc76b1ec8e244d429 diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 2ed47fdf78..ab10d5b010 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -291,6 +291,13 @@ std::optional CameraServerImpl::process_camera_information_re const uint16_t camera_definition_version = 0; auto camera_definition_uri = ""; + // capability flags are determined by subscriptions + uint32_t capability_flags{}; + + if (_take_photo_callback) { + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE; + } + mavlink_message_t msg{}; mavlink_msg_camera_information_pack( _parent->get_own_system_id(), @@ -306,7 +313,7 @@ std::optional CameraServerImpl::process_camera_information_re _information.horizontal_resolution_px, _information.vertical_resolution_px, lens_id, - CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE, + capability_flags, camera_definition_version, camera_definition_uri); @@ -561,8 +568,7 @@ CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::Comm if (!_take_photo_callback) { LogDebug() << "image capture requested with no take photo subscriber"; - return _parent->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED); + return _parent->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } // single image capture From af28bead964ebfc02db36af892c5d7c17046e4a5 Mon Sep 17 00:00:00 2001 From: David Lechner Date: Thu, 17 Feb 2022 14:11:54 -0600 Subject: [PATCH 5/6] camera_server: implement additional information fields --- examples/camera_server/camera_server.cpp | 8 +- proto | 2 +- .../plugins/camera_server/camera_server.cpp | 10 +- .../camera_server/camera_server_impl.cpp | 71 ++++- .../camera_server/camera_server_impl.h | 2 + .../plugins/camera_server/camera_server.h | 18 +- .../camera_server/camera_server.grpc.pb.h | 24 +- .../camera_server/camera_server.pb.cc | 299 +++++++++++++----- .../camera_server/camera_server.pb.h | 216 ++++++++++++- .../camera_server_service_impl.h | 16 + 10 files changed, 545 insertions(+), 121 deletions(-) diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index c65e624376..19ba845b2c 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -83,9 +83,10 @@ int main(int argc, char** argv) // Finally call set_information() to "activate" the camera plugin. - camera_server->set_information({ + auto ret = camera_server->set_information({ .vendor_name = "MAVSDK", .model_name = "Example Camera Server", + .firmware_version = "1.0.0", .focal_length_mm = 3.0, .horizontal_sensor_size_mm = 3.68, .vertical_sensor_size_mm = 2.76, @@ -93,6 +94,11 @@ int main(int argc, char** argv) .vertical_resolution_px = 2464, }); + if (ret != CameraServer::Result::Success) { + std::cerr << "Failed to set camera info, exiting" << std::endl; + exit(1); + } + std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") << " system ID " << +system->get_system_id() << std::endl; } diff --git a/proto b/proto index 4b3f0573dd..dbb333e731 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 4b3f0573dddaf1de7efcc1efc76b1ec8e244d429 +Subproject commit dbb333e731ff411693b3e830d76e225ecbdc5e48 diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index d5e47cc2e5..80a18207f5 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -50,6 +50,7 @@ CameraServer::Result CameraServer::respond_take_photo(CaptureInfo capture_info) bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && + (rhs.firmware_version == lhs.firmware_version) && ((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) || rhs.focal_length_mm == lhs.focal_length_mm) && ((std::isnan(rhs.horizontal_sensor_size_mm) && @@ -58,7 +59,10 @@ bool operator==(const CameraServer::Information& lhs, const CameraServer::Inform ((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) || rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) && (rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) && - (rhs.vertical_resolution_px == lhs.vertical_resolution_px); + (rhs.vertical_resolution_px == lhs.vertical_resolution_px) && + (rhs.lens_id == lhs.lens_id) && + (rhs.definition_file_version == lhs.definition_file_version) && + (rhs.definition_file_uri == lhs.definition_file_uri); } std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information) @@ -67,11 +71,15 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Information const& inf str << "information:" << '\n' << "{\n"; str << " vendor_name: " << information.vendor_name << '\n'; str << " model_name: " << information.model_name << '\n'; + str << " firmware_version: " << information.firmware_version << '\n'; str << " focal_length_mm: " << information.focal_length_mm << '\n'; str << " horizontal_sensor_size_mm: " << information.horizontal_sensor_size_mm << '\n'; str << " vertical_sensor_size_mm: " << information.vertical_sensor_size_mm << '\n'; str << " horizontal_resolution_px: " << information.horizontal_resolution_px << '\n'; str << " vertical_resolution_px: " << information.vertical_resolution_px << '\n'; + str << " lens_id: " << information.lens_id << '\n'; + str << " definition_file_version: " << information.definition_file_version << '\n'; + str << " definition_file_uri: " << information.definition_file_uri << '\n'; str << '}'; return str; } diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index ab10d5b010..430db09bed 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -145,10 +145,66 @@ void CameraServerImpl::disable() stop_image_capture_interval(); } +/** + * Parses a firmware version string. + * + * The string must be in the format "[.[.[.]]]". + * + * @param [in] version_str The version string to be parsed. + * @return True if parsing was successful, otherwise false. + */ +bool CameraServerImpl::parse_version_string(const std::string& version_str) +{ + uint32_t unused; + + return parse_version_string(version_str, unused); +} + +/** + * Parses a firmware version string. + * + * The string must be in the format "[.[.[.]]]". + * + * @param [in] version_str The version string to be parsed. + * @param [out] version Encoded version integer for passing to MAVSDK messages. + * @return True if parsing was successful, otherwise false. + */ +bool CameraServerImpl::parse_version_string(const std::string& version_str, uint32_t& version) +{ + // empty string means no version + if (version_str.empty()) { + version = 0; + + return true; + } + + uint8_t major{}, minor{}, patch{}, dev{}; + + auto ret = sscanf(version_str.c_str(), "%hhu.%hhu.%hhu.%hhu", &major, &minor, &patch, &dev); + + if (ret == EOF) { + return false; + } + + // pack version according to MAVLINK spec + version = dev << 24 | patch << 16 | minor << 8 | major; + + return true; +} + CameraServer::Result CameraServerImpl::set_information(CameraServer::Information information) { + if (!parse_version_string(information.firmware_version)) { + LogDebug() << "incorrectly formatted firmware version string: " + << information.firmware_version; + return CameraServer::Result::WrongArgument; + } + + // TODO: validate information.definition_file_uri + _is_information_set = true; _information = information; + return CameraServer::Result::Success; } @@ -285,11 +341,10 @@ std::optional CameraServerImpl::process_camera_information_re // FIXME: why is this needed to prevent dropping messages? std::this_thread::sleep_for(std::chrono::milliseconds(100)); - // unsupported items - const uint32_t firmware_version = 0; - const uint8_t lens_id = 0; - const uint16_t camera_definition_version = 0; - auto camera_definition_uri = ""; + // It is safe to ignore the return value of parse_version_string() here + // since the string was already validated in set_information(). + uint32_t firmware_version; + parse_version_string(_information.firmware_version, firmware_version); // capability flags are determined by subscriptions uint32_t capability_flags{}; @@ -312,10 +367,10 @@ std::optional CameraServerImpl::process_camera_information_re _information.vertical_sensor_size_mm, _information.horizontal_resolution_px, _information.vertical_resolution_px, - lens_id, + _information.lens_id, capability_flags, - camera_definition_version, - camera_definition_uri); + _information.definition_file_version, + _information.definition_file_uri.c_str()); _parent->send_message(msg); LogDebug() << "sent info msg"; diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 3c72cc7ef5..14f1ec6f88 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -49,6 +49,8 @@ class CameraServerImpl : public PluginImplBase { CameraServer::TakePhotoCallback _take_photo_callback{}; + 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); void stop_image_capture_interval(); 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 259bd10975..4025bbc173 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 @@ -62,11 +62,18 @@ class CameraServer : public PluginBase { struct Information { std::string vendor_name{}; /**< @brief Name of the camera vendor */ std::string model_name{}; /**< @brief Name of the camera model */ + std::string firmware_version{}; /**< @brief Camera firmware version in + '...' format */ float focal_length_mm{}; /**< @brief Focal length */ float horizontal_sensor_size_mm{}; /**< @brief Horizontal sensor size */ float vertical_sensor_size_mm{}; /**< @brief Vertical sensor size */ uint32_t horizontal_resolution_px{}; /**< @brief Horizontal image resolution in pixels */ uint32_t vertical_resolution_px{}; /**< @brief Vertical image resolution in pixels */ + uint32_t lens_id{}; /**< @brief Lens ID */ + uint32_t + definition_file_version{}; /**< @brief Camera definition file version (iteration) */ + std::string + definition_file_uri{}; /**< @brief Camera definition URI (http or mavlink ftp) */ }; /** @@ -198,7 +205,8 @@ class CameraServer : public PluginBase { using ResultCallback = std::function; /** - * @brief Sets the camera information + * @brief Sets the camera information. This must be called as soon as the camera server is + * created. * * This function is blocking. * @@ -207,7 +215,8 @@ class CameraServer : public PluginBase { Result set_information(Information information) const; /** - * @brief Sets the camera capture status + * @brief Sets image capture in progress status flags. This should be set to true when the + * camera is busy taking a photo and false when it is done. * * This function is blocking. * @@ -222,12 +231,13 @@ class CameraServer : public PluginBase { using TakePhotoCallback = std::function; /** - * @brief Subscribe to single-image capture commands + * @brief Subscribe to image capture requests. Each request received should respond to using + * RespondTakePhoto. */ void subscribe_take_photo(TakePhotoCallback callback); /** - * @brief Respond to a single-image capture command. + * @brief Respond to an image capture request from SubscribeTakePhoto. * * This function is blocking. * 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 a6cbce2438..1ada1bcd05 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 @@ -38,7 +38,7 @@ class CameraServerService final { class StubInterface { public: virtual ~StubInterface() {} - // Sets the camera information + // Sets the camera information. This must be called as soon as the camera server is created. virtual ::grpc::Status SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>> AsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>>(AsyncSetInformationRaw(context, request, cq)); @@ -46,7 +46,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>> PrepareAsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>>(PrepareAsyncSetInformationRaw(context, request, cq)); } - // Sets the camera capture status + // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual ::grpc::Status SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>> AsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(AsyncSetInProgressRaw(context, request, cq)); @@ -54,7 +54,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>> PrepareAsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(PrepareAsyncSetInProgressRaw(context, request, cq)); } - // Subscribe to single-image capture commands + // Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>> SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(SubscribeTakePhotoRaw(context, request)); } @@ -64,7 +64,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>> PrepareAsyncSubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(PrepareAsyncSubscribeTakePhotoRaw(context, request, cq)); } - // Respond to a single-image capture command. + // Respond to an image capture request from SubscribeTakePhoto. virtual ::grpc::Status RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> AsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(AsyncRespondTakePhotoRaw(context, request, cq)); @@ -75,15 +75,15 @@ class CameraServerService final { class async_interface { public: virtual ~async_interface() {} - // Sets the camera information + // Sets the camera information. This must be called as soon as the camera server is created. virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function) = 0; virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Sets the camera capture status + // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) = 0; virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Subscribe to single-image capture commands + // Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. virtual void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) = 0; - // Respond to a single-image capture command. + // Respond to an image capture request from SubscribeTakePhoto. virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) = 0; virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; @@ -175,13 +175,13 @@ class CameraServerService final { public: Service(); virtual ~Service(); - // Sets the camera information + // Sets the camera information. This must be called as soon as the camera server is created. virtual ::grpc::Status SetInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response); - // Sets the camera capture status + // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual ::grpc::Status SetInProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response); - // Subscribe to single-image capture commands + // Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. virtual ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer); - // Respond to a single-image capture command. + // Respond to an image capture request from SubscribeTakePhoto. virtual ::grpc::Status RespondTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response); }; template 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 5cb1accb83..882e9d27f1 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 @@ -119,11 +119,15 @@ constexpr Information::Information( ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) : vendor_name_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) , model_name_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , firmware_version_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , definition_file_uri_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) , focal_length_mm_(0) , horizontal_sensor_size_mm_(0) , vertical_sensor_size_mm_(0) , horizontal_resolution_px_(0u) - , vertical_resolution_px_(0u){} + , vertical_resolution_px_(0u) + , lens_id_(0u) + , definition_file_version_(0u){} struct InformationDefaultTypeInternal { constexpr InformationDefaultTypeInternal() : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} @@ -257,11 +261,15 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_camera_5fserver_2fcamera_5fser ~0u, // no _weak_field_map_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vendor_name_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, model_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, firmware_version_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, focal_length_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, horizontal_sensor_size_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vertical_sensor_size_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, horizontal_resolution_px_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vertical_resolution_px_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, lens_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, definition_file_version_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, definition_file_uri_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _internal_metadata_), ~0u, // no _extensions_ @@ -309,10 +317,10 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB { 36, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, { 42, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, { 48, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 60, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 69, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 78, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 89, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 64, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 73, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 82, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 93, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, }; static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = { @@ -350,51 +358,54 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "\030\001 \001(\0132%.mavsdk.rpc.camera_server.Captur" "eInfo\"f\n\030RespondTakePhotoResponse\022J\n\024cam" "era_server_result\030\001 \001(\0132,.mavsdk.rpc.cam" - "era_server.CameraServerResult\"\325\001\n\013Inform" + "era_server.CameraServerResult\"\276\002\n\013Inform" "ation\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name" - "\030\002 \001(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031horiz" - "ontal_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_s" - "ensor_size_mm\030\005 \001(\002\022 \n\030horizontal_resolu" - "tion_px\030\006 \001(\r\022\036\n\026vertical_resolution_px\030" - "\007 \001(\r\"q\n\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022" - "\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_altit" - "ude_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\001" - "y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\0224\n\010po" - "sition\030\001 \001(\0132\".mavsdk.rpc.camera_server." - "Position\022A\n\023attitude_quaternion\030\002 \001(\0132$." - "mavsdk.rpc.camera_server.Quaternion\022\023\n\013t" - "ime_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005" - "index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022Camera" - "ServerResult\022C\n\006result\030\001 \001(\01623.mavsdk.rp" - "c.camera_server.CameraServerResult.Resul" - "t\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESU" - "LT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESU" - "LT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRES" - "ULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT" - "_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n" - "\020RESULT_NO_SYSTEM\020\0102\211\004\n\023CameraServerServ" - "ice\022y\n\016SetInformation\022/.mavsdk.rpc.camer" - "a_server.SetInformationRequest\0320.mavsdk." - "rpc.camera_server.SetInformationResponse" - "\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.cam" - "era_server.SetInProgressRequest\032/.mavsdk" - ".rpc.camera_server.SetInProgressResponse" - "\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rp" - "c.camera_server.SubscribeTakePhotoReques" - "t\032+.mavsdk.rpc.camera_server.TakePhotoRe" - "sponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mav" - "sdk.rpc.camera_server.RespondTakePhotoRe" - "quest\0322.mavsdk.rpc.camera_server.Respond" - "TakePhotoResponse\"\004\200\265\030\001B,\n\027io.mavsdk.cam" - "era_serverB\021CameraServerProtob\006proto3" + "\030\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017foca" + "l_length_mm\030\004 \001(\002\022!\n\031horizontal_sensor_s" + "ize_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\"q\n\010Positi" + "on\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_de" + "g\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023" + "relative_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022" + "\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 " + "\001(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\"." + "mavsdk.rpc.camera_server.Position\022A\n\023att" + "itude_quaternion\030\002 \001(\0132$.mavsdk.rpc.came" + "ra_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\010" + "file_url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n" + "\006result\030\001 \001(\01623.mavsdk.rpc.camera_server" + ".CameraServerResult.Result\022\022\n\nresult_str" + "\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n" + "\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020" + "\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n" + "\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025R" + "ESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYST" + "EM\020\0102\211\004\n\023CameraServerService\022y\n\016SetInfor" + "mation\022/.mavsdk.rpc.camera_server.SetInf" + "ormationRequest\0320.mavsdk.rpc.camera_serv" + "er.SetInformationResponse\"\004\200\265\030\001\022v\n\rSetIn" + "Progress\022..mavsdk.rpc.camera_server.SetI" + "nProgressRequest\032/.mavsdk.rpc.camera_ser" + "ver.SetInProgressResponse\"\004\200\265\030\001\022~\n\022Subsc" + "ribeTakePhoto\0223.mavsdk.rpc.camera_server" + ".SubscribeTakePhotoRequest\032+.mavsdk.rpc." + "camera_server.TakePhotoResponse\"\004\200\265\030\0000\001\022" + "\177\n\020RespondTakePhoto\0221.mavsdk.rpc.camera_" + "server.RespondTakePhotoRequest\0322.mavsdk." + "rpc.camera_server.RespondTakePhotoRespon" + "se\"\004\200\265\030\001B,\n\027io.mavsdk.camera_serverB\021Cam" + "eraServerProtob\006proto3" ; static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, }; static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once; const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { - false, false, 2237, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", + false, false, 2342, 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, 13, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto, file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto, file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto, @@ -2041,19 +2052,31 @@ Information::Information(const Information& from) model_name_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_model_name(), GetArenaForAllocation()); } + firmware_version_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_firmware_version().empty()) { + firmware_version_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_firmware_version(), + GetArenaForAllocation()); + } + definition_file_uri_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_definition_file_uri().empty()) { + definition_file_uri_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_definition_file_uri(), + GetArenaForAllocation()); + } ::memcpy(&focal_length_mm_, &from.focal_length_mm_, - static_cast(reinterpret_cast(&vertical_resolution_px_) - - reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); + static_cast(reinterpret_cast(&definition_file_version_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(definition_file_version_)); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Information) } inline void Information::SharedCtor() { vendor_name_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); model_name_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +firmware_version_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +definition_file_uri_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); ::memset(reinterpret_cast(this) + static_cast( reinterpret_cast(&focal_length_mm_) - reinterpret_cast(this)), - 0, static_cast(reinterpret_cast(&vertical_resolution_px_) - - reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); + 0, static_cast(reinterpret_cast(&definition_file_version_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(definition_file_version_)); } Information::~Information() { @@ -2067,6 +2090,8 @@ inline void Information::SharedDtor() { GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); vendor_name_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); model_name_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + firmware_version_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + definition_file_uri_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); } void Information::ArenaDtor(void* object) { @@ -2087,9 +2112,11 @@ void Information::Clear() { vendor_name_.ClearToEmpty(); model_name_.ClearToEmpty(); + firmware_version_.ClearToEmpty(); + definition_file_uri_.ClearToEmpty(); ::memset(&focal_length_mm_, 0, static_cast( - reinterpret_cast(&vertical_resolution_px_) - - reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); + reinterpret_cast(&definition_file_version_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(definition_file_version_)); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } @@ -2117,41 +2144,73 @@ const char* Information::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID CHK_(ptr); } else goto handle_unusual; continue; - // float focal_length_mm = 3; + // string firmware_version = 3; case 3: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 29)) { - focal_length_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 26)) { + auto str = _internal_mutable_firmware_version(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.firmware_version")); + CHK_(ptr); } else goto handle_unusual; continue; - // float horizontal_sensor_size_mm = 4; + // float focal_length_mm = 4; case 4: if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 37)) { - horizontal_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + focal_length_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else goto handle_unusual; continue; - // float vertical_sensor_size_mm = 5; + // float horizontal_sensor_size_mm = 5; case 5: if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 45)) { - vertical_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + horizontal_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else goto handle_unusual; continue; - // uint32 horizontal_resolution_px = 6; + // float vertical_sensor_size_mm = 6; case 6: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 48)) { - horizontal_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 53)) { + vertical_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); } else goto handle_unusual; continue; - // uint32 vertical_resolution_px = 7; + // uint32 horizontal_resolution_px = 7; case 7: if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 56)) { + horizontal_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // uint32 vertical_resolution_px = 8; + case 8: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 64)) { vertical_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); } else goto handle_unusual; continue; + // uint32 lens_id = 9; + case 9: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 72)) { + lens_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // uint32 definition_file_version = 10; + case 10: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 80)) { + definition_file_version_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // string definition_file_uri = 11; + case 11: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 90)) { + auto str = _internal_mutable_definition_file_uri(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.definition_file_uri")); + CHK_(ptr); + } else goto handle_unusual; + continue; default: { handle_unusual: if ((tag == 0) || ((tag & 7) == 4)) { @@ -2201,34 +2260,66 @@ ::PROTOBUF_NAMESPACE_ID::uint8* Information::_InternalSerialize( 2, this->_internal_model_name(), target); } - // float focal_length_mm = 3; + // string firmware_version = 3; + if (!this->_internal_firmware_version().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_firmware_version().data(), static_cast(this->_internal_firmware_version().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.camera_server.Information.firmware_version"); + target = stream->WriteStringMaybeAliased( + 3, this->_internal_firmware_version(), target); + } + + // float focal_length_mm = 4; if (!(this->_internal_focal_length_mm() <= 0 && this->_internal_focal_length_mm() >= 0)) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(3, this->_internal_focal_length_mm(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(4, this->_internal_focal_length_mm(), target); } - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; if (!(this->_internal_horizontal_sensor_size_mm() <= 0 && this->_internal_horizontal_sensor_size_mm() >= 0)) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(4, this->_internal_horizontal_sensor_size_mm(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(5, this->_internal_horizontal_sensor_size_mm(), target); } - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; if (!(this->_internal_vertical_sensor_size_mm() <= 0 && this->_internal_vertical_sensor_size_mm() >= 0)) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(5, this->_internal_vertical_sensor_size_mm(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(6, this->_internal_vertical_sensor_size_mm(), target); } - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; if (this->_internal_horizontal_resolution_px() != 0) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(6, this->_internal_horizontal_resolution_px(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(7, this->_internal_horizontal_resolution_px(), target); } - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; if (this->_internal_vertical_resolution_px() != 0) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(7, this->_internal_vertical_resolution_px(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(8, this->_internal_vertical_resolution_px(), target); + } + + // uint32 lens_id = 9; + if (this->_internal_lens_id() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(9, this->_internal_lens_id(), target); + } + + // uint32 definition_file_version = 10; + if (this->_internal_definition_file_version() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(10, this->_internal_definition_file_version(), target); + } + + // string definition_file_uri = 11; + if (!this->_internal_definition_file_uri().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_definition_file_uri().data(), static_cast(this->_internal_definition_file_uri().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.camera_server.Information.definition_file_uri"); + target = stream->WriteStringMaybeAliased( + 11, this->_internal_definition_file_uri(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -2261,35 +2352,63 @@ size_t Information::ByteSizeLong() const { this->_internal_model_name()); } - // float focal_length_mm = 3; + // string firmware_version = 3; + if (!this->_internal_firmware_version().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_firmware_version()); + } + + // string definition_file_uri = 11; + if (!this->_internal_definition_file_uri().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_definition_file_uri()); + } + + // float focal_length_mm = 4; if (!(this->_internal_focal_length_mm() <= 0 && this->_internal_focal_length_mm() >= 0)) { total_size += 1 + 4; } - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; if (!(this->_internal_horizontal_sensor_size_mm() <= 0 && this->_internal_horizontal_sensor_size_mm() >= 0)) { total_size += 1 + 4; } - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; if (!(this->_internal_vertical_sensor_size_mm() <= 0 && this->_internal_vertical_sensor_size_mm() >= 0)) { total_size += 1 + 4; } - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; if (this->_internal_horizontal_resolution_px() != 0) { total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( this->_internal_horizontal_resolution_px()); } - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; if (this->_internal_vertical_resolution_px() != 0) { total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( this->_internal_vertical_resolution_px()); } + // uint32 lens_id = 9; + if (this->_internal_lens_id() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( + this->_internal_lens_id()); + } + + // uint32 definition_file_version = 10; + if (this->_internal_definition_file_version() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( + this->_internal_definition_file_version()); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( _internal_metadata_, total_size, &_cached_size_); @@ -2324,6 +2443,12 @@ void Information::MergeFrom(const Information& from) { if (!from._internal_model_name().empty()) { _internal_set_model_name(from._internal_model_name()); } + if (!from._internal_firmware_version().empty()) { + _internal_set_firmware_version(from._internal_firmware_version()); + } + if (!from._internal_definition_file_uri().empty()) { + _internal_set_definition_file_uri(from._internal_definition_file_uri()); + } if (!(from._internal_focal_length_mm() <= 0 && from._internal_focal_length_mm() >= 0)) { _internal_set_focal_length_mm(from._internal_focal_length_mm()); } @@ -2339,6 +2464,12 @@ void Information::MergeFrom(const Information& from) { if (from._internal_vertical_resolution_px() != 0) { _internal_set_vertical_resolution_px(from._internal_vertical_resolution_px()); } + if (from._internal_lens_id() != 0) { + _internal_set_lens_id(from._internal_lens_id()); + } + if (from._internal_definition_file_version() != 0) { + _internal_set_definition_file_version(from._internal_definition_file_version()); + } _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } @@ -2366,9 +2497,19 @@ void Information::InternalSwap(Information* other) { &model_name_, GetArenaForAllocation(), &other->model_name_, other->GetArenaForAllocation() ); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &firmware_version_, GetArenaForAllocation(), + &other->firmware_version_, other->GetArenaForAllocation() + ); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &definition_file_uri_, GetArenaForAllocation(), + &other->definition_file_uri_, other->GetArenaForAllocation() + ); ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(Information, vertical_resolution_px_) - + sizeof(Information::vertical_resolution_px_) + PROTOBUF_FIELD_OFFSET(Information, definition_file_version_) + + sizeof(Information::definition_file_version_) - PROTOBUF_FIELD_OFFSET(Information, focal_length_mm_)>( reinterpret_cast(&focal_length_mm_), reinterpret_cast(&other->focal_length_mm_)); 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 6828a984e1..721d3bef45 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 @@ -1434,11 +1434,15 @@ class Information final : enum : int { kVendorNameFieldNumber = 1, kModelNameFieldNumber = 2, - kFocalLengthMmFieldNumber = 3, - kHorizontalSensorSizeMmFieldNumber = 4, - kVerticalSensorSizeMmFieldNumber = 5, - kHorizontalResolutionPxFieldNumber = 6, - kVerticalResolutionPxFieldNumber = 7, + kFirmwareVersionFieldNumber = 3, + kDefinitionFileUriFieldNumber = 11, + kFocalLengthMmFieldNumber = 4, + kHorizontalSensorSizeMmFieldNumber = 5, + kVerticalSensorSizeMmFieldNumber = 6, + kHorizontalResolutionPxFieldNumber = 7, + kVerticalResolutionPxFieldNumber = 8, + kLensIdFieldNumber = 9, + kDefinitionFileVersionFieldNumber = 10, }; // string vendor_name = 1; void clear_vendor_name(); @@ -1468,7 +1472,35 @@ class Information final : std::string* _internal_mutable_model_name(); public: - // float focal_length_mm = 3; + // string firmware_version = 3; + void clear_firmware_version(); + const std::string& firmware_version() const; + template + void set_firmware_version(ArgT0&& arg0, ArgT... args); + std::string* mutable_firmware_version(); + PROTOBUF_MUST_USE_RESULT std::string* release_firmware_version(); + void set_allocated_firmware_version(std::string* firmware_version); + 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(ArgT0&& arg0, ArgT... args); + std::string* mutable_definition_file_uri(); + PROTOBUF_MUST_USE_RESULT std::string* release_definition_file_uri(); + void set_allocated_definition_file_uri(std::string* definition_file_uri); + 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); @@ -1477,7 +1509,7 @@ class Information final : void _internal_set_focal_length_mm(float value); public: - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; void clear_horizontal_sensor_size_mm(); float horizontal_sensor_size_mm() const; void set_horizontal_sensor_size_mm(float value); @@ -1486,7 +1518,7 @@ class Information final : void _internal_set_horizontal_sensor_size_mm(float value); public: - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; void clear_vertical_sensor_size_mm(); float vertical_sensor_size_mm() const; void set_vertical_sensor_size_mm(float value); @@ -1495,7 +1527,7 @@ class Information final : void _internal_set_vertical_sensor_size_mm(float value); public: - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; void clear_horizontal_resolution_px(); ::PROTOBUF_NAMESPACE_ID::uint32 horizontal_resolution_px() const; void set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); @@ -1504,7 +1536,7 @@ class Information final : void _internal_set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); public: - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; void clear_vertical_resolution_px(); ::PROTOBUF_NAMESPACE_ID::uint32 vertical_resolution_px() const; void set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); @@ -1513,6 +1545,24 @@ class Information final : void _internal_set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); public: + // uint32 lens_id = 9; + void clear_lens_id(); + ::PROTOBUF_NAMESPACE_ID::uint32 lens_id() const; + void set_lens_id(::PROTOBUF_NAMESPACE_ID::uint32 value); + private: + ::PROTOBUF_NAMESPACE_ID::uint32 _internal_lens_id() const; + void _internal_set_lens_id(::PROTOBUF_NAMESPACE_ID::uint32 value); + public: + + // uint32 definition_file_version = 10; + void clear_definition_file_version(); + ::PROTOBUF_NAMESPACE_ID::uint32 definition_file_version() const; + void set_definition_file_version(::PROTOBUF_NAMESPACE_ID::uint32 value); + private: + ::PROTOBUF_NAMESPACE_ID::uint32 _internal_definition_file_version() const; + void _internal_set_definition_file_version(::PROTOBUF_NAMESPACE_ID::uint32 value); + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) private: class _Internal; @@ -1522,11 +1572,15 @@ class Information final : typedef void DestructorSkippable_; ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr firmware_version_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr definition_file_uri_; float focal_length_mm_; float horizontal_sensor_size_mm_; float vertical_sensor_size_mm_; ::PROTOBUF_NAMESPACE_ID::uint32 horizontal_resolution_px_; ::PROTOBUF_NAMESPACE_ID::uint32 vertical_resolution_px_; + ::PROTOBUF_NAMESPACE_ID::uint32 lens_id_; + ::PROTOBUF_NAMESPACE_ID::uint32 definition_file_version_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; }; @@ -3005,7 +3059,53 @@ inline void Information::set_allocated_model_name(std::string* model_name) { // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.model_name) } -// float focal_length_mm = 3; +// string firmware_version = 3; +inline void Information::clear_firmware_version() { + firmware_version_.ClearToEmpty(); +} +inline const std::string& Information::firmware_version() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.firmware_version) + return _internal_firmware_version(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void Information::set_firmware_version(ArgT0&& arg0, ArgT... args) { + + firmware_version_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.firmware_version) +} +inline std::string* Information::mutable_firmware_version() { + std::string* _s = _internal_mutable_firmware_version(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.Information.firmware_version) + return _s; +} +inline const std::string& Information::_internal_firmware_version() const { + return firmware_version_.Get(); +} +inline void Information::_internal_set_firmware_version(const std::string& value) { + + firmware_version_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* Information::_internal_mutable_firmware_version() { + + return firmware_version_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* Information::release_firmware_version() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.Information.firmware_version) + return firmware_version_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void Information::set_allocated_firmware_version(std::string* firmware_version) { + if (firmware_version != nullptr) { + + } else { + + } + firmware_version_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), firmware_version, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.firmware_version) +} + +// float focal_length_mm = 4; inline void Information::clear_focal_length_mm() { focal_length_mm_ = 0; } @@ -3025,7 +3125,7 @@ inline void Information::set_focal_length_mm(float value) { // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.focal_length_mm) } -// float horizontal_sensor_size_mm = 4; +// float horizontal_sensor_size_mm = 5; inline void Information::clear_horizontal_sensor_size_mm() { horizontal_sensor_size_mm_ = 0; } @@ -3045,7 +3145,7 @@ inline void Information::set_horizontal_sensor_size_mm(float value) { // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.horizontal_sensor_size_mm) } -// float vertical_sensor_size_mm = 5; +// float vertical_sensor_size_mm = 6; inline void Information::clear_vertical_sensor_size_mm() { vertical_sensor_size_mm_ = 0; } @@ -3065,7 +3165,7 @@ inline void Information::set_vertical_sensor_size_mm(float value) { // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.vertical_sensor_size_mm) } -// uint32 horizontal_resolution_px = 6; +// uint32 horizontal_resolution_px = 7; inline void Information::clear_horizontal_resolution_px() { horizontal_resolution_px_ = 0u; } @@ -3085,7 +3185,7 @@ inline void Information::set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::u // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.horizontal_resolution_px) } -// uint32 vertical_resolution_px = 7; +// uint32 vertical_resolution_px = 8; inline void Information::clear_vertical_resolution_px() { vertical_resolution_px_ = 0u; } @@ -3105,6 +3205,92 @@ inline void Information::set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uin // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.vertical_resolution_px) } +// uint32 lens_id = 9; +inline void Information::clear_lens_id() { + lens_id_ = 0u; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::_internal_lens_id() const { + return lens_id_; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::lens_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.lens_id) + return _internal_lens_id(); +} +inline void Information::_internal_set_lens_id(::PROTOBUF_NAMESPACE_ID::uint32 value) { + + lens_id_ = value; +} +inline void Information::set_lens_id(::PROTOBUF_NAMESPACE_ID::uint32 value) { + _internal_set_lens_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.lens_id) +} + +// uint32 definition_file_version = 10; +inline void Information::clear_definition_file_version() { + definition_file_version_ = 0u; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::_internal_definition_file_version() const { + return definition_file_version_; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::definition_file_version() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.definition_file_version) + return _internal_definition_file_version(); +} +inline void Information::_internal_set_definition_file_version(::PROTOBUF_NAMESPACE_ID::uint32 value) { + + definition_file_version_ = value; +} +inline void Information::set_definition_file_version(::PROTOBUF_NAMESPACE_ID::uint32 value) { + _internal_set_definition_file_version(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.definition_file_version) +} + +// string definition_file_uri = 11; +inline void Information::clear_definition_file_uri() { + definition_file_uri_.ClearToEmpty(); +} +inline const std::string& Information::definition_file_uri() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.definition_file_uri) + return _internal_definition_file_uri(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void Information::set_definition_file_uri(ArgT0&& arg0, ArgT... args) { + + definition_file_uri_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.definition_file_uri) +} +inline std::string* Information::mutable_definition_file_uri() { + std::string* _s = _internal_mutable_definition_file_uri(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.Information.definition_file_uri) + return _s; +} +inline const std::string& Information::_internal_definition_file_uri() const { + return definition_file_uri_.Get(); +} +inline void Information::_internal_set_definition_file_uri(const std::string& value) { + + definition_file_uri_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* Information::_internal_mutable_definition_file_uri() { + + return definition_file_uri_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* Information::release_definition_file_uri() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.Information.definition_file_uri) + return definition_file_uri_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void Information::set_allocated_definition_file_uri(std::string* definition_file_uri) { + if (definition_file_uri != nullptr) { + + } else { + + } + definition_file_uri_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), definition_file_uri, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.definition_file_uri) +} + // ------------------------------------------------------------------- // Position 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 427d58a0e4..648e50da9a 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 @@ -48,6 +48,8 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer rpc_obj->set_model_name(information.model_name); + rpc_obj->set_firmware_version(information.firmware_version); + rpc_obj->set_focal_length_mm(information.focal_length_mm); rpc_obj->set_horizontal_sensor_size_mm(information.horizontal_sensor_size_mm); @@ -58,6 +60,12 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer rpc_obj->set_vertical_resolution_px(information.vertical_resolution_px); + rpc_obj->set_lens_id(information.lens_id); + + rpc_obj->set_definition_file_version(information.definition_file_version); + + rpc_obj->set_definition_file_uri(information.definition_file_uri); + return rpc_obj; } @@ -70,6 +78,8 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer obj.model_name = information.model_name(); + obj.firmware_version = information.firmware_version(); + obj.focal_length_mm = information.focal_length_mm(); obj.horizontal_sensor_size_mm = information.horizontal_sensor_size_mm(); @@ -80,6 +90,12 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer obj.vertical_resolution_px = information.vertical_resolution_px(); + obj.lens_id = information.lens_id(); + + obj.definition_file_version = information.definition_file_version(); + + obj.definition_file_uri = information.definition_file_uri(); + return obj; } From 1528f0cf05fcae55be6941694f7d935d0fa378b0 Mon Sep 17 00:00:00 2001 From: David Lechner Date: Thu, 17 Feb 2022 14:37:49 -0600 Subject: [PATCH 6/6] camera_server: improve in_progress state --- examples/camera_server/camera_server.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 19ba845b2c..bed24d1e0e 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -45,8 +45,10 @@ int main(int argc, char** argv) // First add all subscriptions. This defines the camera capabilities. camera_server->subscribe_take_photo( - [camera_server, &all_camera_servers](CameraServer::Result result, int32_t index) { - camera_server->set_in_progress(true); + [&all_camera_servers](CameraServer::Result result, int32_t index) { + for (auto&& [key, value] : all_camera_servers) { + value->set_in_progress(true); + } std::cout << "taking a picture (" << +index << ")..." << std::endl; @@ -62,9 +64,10 @@ int main(int argc, char** argv) duration_cast(system_clock::now().time_since_epoch()).count(); auto success = true; - camera_server->set_in_progress(false); + for (auto&& [key, value] : all_camera_servers) { + value->set_in_progress(false); + } - // hack to simulate broadcast and keep total count in sync for (auto&& [key, value] : all_camera_servers) { value->respond_take_photo({ .position = position, @@ -79,6 +82,8 @@ int main(int argc, char** argv) // Then set the initial state of everything. + // TODO: this state is not guaranteed, e.g. a new system appears + // while a capture is in progress camera_server->set_in_progress(false); // Finally call set_information() to "activate" the camera plugin.