From f306291158a064a86606b1daae6e873c9182a3c9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 21 May 2024 16:22:05 +0200 Subject: [PATCH 1/9] component_metadata: add example --- examples/CMakeLists.txt | 1 + examples/component_metadata/CMakeLists.txt | 22 +++++ .../component_metadata/component_metadata.cpp | 81 +++++++++++++++++++ 3 files changed, 104 insertions(+) create mode 100644 examples/component_metadata/CMakeLists.txt create mode 100644 examples/component_metadata/component_metadata.cpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 554936eb8..11ddc7112 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -15,6 +15,7 @@ add_subdirectory(camera) add_subdirectory(camera_server) add_subdirectory(camera_settings) add_subdirectory(camera_zoom) +add_subdirectory(component_metadata) add_subdirectory(disconnect) add_subdirectory(fly_mission) add_subdirectory(fly_multiple_drones) diff --git a/examples/component_metadata/CMakeLists.txt b/examples/component_metadata/CMakeLists.txt new file mode 100644 index 000000000..79a0df16b --- /dev/null +++ b/examples/component_metadata/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(component_metadata) + +add_executable(component_metadata + component_metadata.cpp +) + +find_package(MAVSDK REQUIRED) + +target_link_libraries(component_metadata + MAVSDK::mavsdk +) + +if(NOT MSVC) + add_compile_options(component_metadata PRIVATE -Wall -Wextra) +else() + add_compile_options(component_metadata PRIVATE -W2) +endif() diff --git a/examples/component_metadata/component_metadata.cpp b/examples/component_metadata/component_metadata.cpp new file mode 100644 index 000000000..069ea06b0 --- /dev/null +++ b/examples/component_metadata/component_metadata.cpp @@ -0,0 +1,81 @@ +// +// Simple example to demonstrate how to use the component metadata interface. +// + +#include +#include +#include +#include +#include +#include + +using namespace mavsdk; + +void usage(const std::string& bin_name) +{ + std::cerr << "Usage : " << bin_name << " \n" + << "Connection URL format should be:\n" + << " For TCP : tcp://[server_host][:server_port]\n" + << " For UDP : udp://[bind_host][:bind_port]\n" + << " For Serial : serial:///path/to/serial/dev[:baudrate]\n" + << "For example, to connect to the simulator use URL: udp://:14540\n"; +} + +int main(int argc, char** argv) +{ + if (argc != 2) { + usage(argv[0]); + return 1; + } + + Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); + + if (connection_result != ConnectionResult::Success) { + std::cerr << "Connection failed: " << connection_result << '\n'; + return 1; + } + + auto system = mavsdk.first_autopilot(3.0); + if (!system) { + std::cerr << "Timed out waiting for system\n"; + return 1; + } + + auto component_metadata = ComponentMetadata{system.value()}; + component_metadata.request_autopilot_component(); + std::promise promise; + auto future = promise.get_future(); + component_metadata.subscribe_metadata_available( + [&promise](ComponentMetadata::MetadataUpdate data) { + if (data.type != ComponentMetadata::MetadataType::AllCompleted) { + std::cout << "Got metadata: type: " << (int)data.type << ", compid: " << data.compid + << std::endl; + } + std::string filename; + switch (data.type) { + case ComponentMetadata::MetadataType::Parameter: + filename = "parameters.json"; + break; + case ComponentMetadata::MetadataType::Events: + filename = "events.json"; + break; + case ComponentMetadata::MetadataType::Actuators: + filename = "actuators.json"; + break; + case ComponentMetadata::MetadataType::AllCompleted: + promise.set_value(true); + break; + } + if (!filename.empty()) { + filename = std::to_string(data.compid) + "_" + filename; + std::cout << " Writing JSON data to " << filename << std::endl; + std::ofstream out(filename); + out << data.json_metadata; + out.close(); + } + }); + + future.get(); + return 0; +} From f4837c68c7769dd36699f653bce69922751ec166 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 22 May 2024 15:31:07 +0200 Subject: [PATCH 2/9] refactor curl: rename Status to HttpStatus to avoid name conflict MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit When moving the component metadata to core, the following error was raised: MAVSDK/src/mavsdk/plugins/camera/camera.cpp:18:7: error: conflicting declaration ‘using mavsdk::Status = struct mavsdk::Camera::Status’ 18 | using Status = Camera::Status; | ^~~~~~ In file included from MAVSDK/src/mavsdk/core/curl_wrapper.h:6, from MAVSDK/src/mavsdk/core/http_loader.h:9, from MAVSDK/src/mavsdk/core/mavlink_component_metadata.h:5, from MAVSDK/src/mavsdk/core/system_impl.h:5, from MAVSDK/src/mavsdk/core/plugin_impl_base.h:2, from MAVSDK/src/mavsdk/plugins/camera/camera_impl.h:8, from MAVSDK/src/mavsdk/plugins/camera/camera.cpp:7: --- src/mavsdk/core/curl_test.cpp | 12 ++++++------ src/mavsdk/core/curl_wrapper.cpp | 8 ++++---- src/mavsdk/core/curl_wrapper_types.h | 4 ++-- .../component_metadata/component_metadata_impl.cpp | 6 +++--- 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/mavsdk/core/curl_test.cpp b/src/mavsdk/core/curl_test.cpp index da8981603..797426c14 100644 --- a/src/mavsdk/core/curl_test.cpp +++ b/src/mavsdk/core/curl_test.cpp @@ -82,11 +82,11 @@ TEST_F(CurlTest, Curl_DownloadFile_WithoutProgressFeedback_FileNotFound) TEST_F(CurlTest, Curl_DownloadFile_ProgressFeedback_Success) { int last_progress; - Status last_status; + HttpStatus last_status; CURLcode last_curl_code; auto progress = [&last_progress, &last_status, &last_curl_code]( - int got_progress, Status status, CURLcode curl_code) -> int { + int got_progress, HttpStatus status, CURLcode curl_code) -> int { last_progress = got_progress; last_status = status; last_curl_code = curl_code; @@ -99,7 +99,7 @@ TEST_F(CurlTest, Curl_DownloadFile_ProgressFeedback_Success) curl_wrapper.download_file_to_path(_file_url_existing_http, _local_path, progress); EXPECT_EQ(success, true); EXPECT_EQ(last_progress, 100); - EXPECT_EQ(last_status, Status::Finished); + EXPECT_EQ(last_status, HttpStatus::Finished); EXPECT_EQ(last_curl_code, CURLcode::CURLE_OK); bool file_exists = check_file_exists(_local_path); @@ -109,11 +109,11 @@ TEST_F(CurlTest, Curl_DownloadFile_ProgressFeedback_Success) TEST_F(CurlTest, Curl_DownloadFile_ProgressFeedback_COULDNT_RESOLVE_HOST) { int last_progress; - Status last_status; + HttpStatus last_status; CURLcode last_curl_code; auto progress = [&last_progress, &last_status, &last_curl_code]( - int got_progress, Status status, CURLcode curl_code) -> int { + int got_progress, HttpStatus status, CURLcode curl_code) -> int { last_progress = got_progress; last_status = status; last_curl_code = curl_code; @@ -126,7 +126,7 @@ TEST_F(CurlTest, Curl_DownloadFile_ProgressFeedback_COULDNT_RESOLVE_HOST) curl_wrapper.download_file_to_path(_file_url_not_existing, _local_path, progress); EXPECT_EQ(success, false); EXPECT_EQ(last_progress, 0); - EXPECT_EQ(last_status, Status::Error); + EXPECT_EQ(last_status, HttpStatus::Error); EXPECT_EQ(last_curl_code, CURLcode::CURLE_COULDNT_RESOLVE_HOST); bool file_exists = check_file_exists(_local_path); diff --git a/src/mavsdk/core/curl_wrapper.cpp b/src/mavsdk/core/curl_wrapper.cpp index 30ef52aa9..bda281ada 100644 --- a/src/mavsdk/core/curl_wrapper.cpp +++ b/src/mavsdk/core/curl_wrapper.cpp @@ -76,14 +76,14 @@ static int download_progress_update( } if (dltotal == 0 || dlnow == 0) { - return myp->progress_callback(0, Status::Idle, CURLcode::CURLE_OK); + return myp->progress_callback(0, HttpStatus::Idle, CURLcode::CURLE_OK); } int percentage = static_cast(100 / dltotal * dlnow); if (percentage > myp->progress_in_percentage) { myp->progress_in_percentage = percentage; - return myp->progress_callback(percentage, Status::Downloading, CURLcode::CURLE_OK); + return myp->progress_callback(percentage, HttpStatus::Downloading, CURLcode::CURLE_OK); } return 0; @@ -113,12 +113,12 @@ bool CurlWrapper::download_file_to_path( if (res == CURLcode::CURLE_OK) { if (nullptr != progress_callback) { - progress_callback(100, Status::Finished, res); + progress_callback(100, HttpStatus::Finished, res); } return true; } else { if (nullptr != progress_callback) { - progress_callback(0, Status::Error, res); + progress_callback(0, HttpStatus::Error, res); } remove(path.c_str()); LogErr() << "Error while downloading file, curl error code: " diff --git a/src/mavsdk/core/curl_wrapper_types.h b/src/mavsdk/core/curl_wrapper_types.h index e51250c2f..3be133e42 100644 --- a/src/mavsdk/core/curl_wrapper_types.h +++ b/src/mavsdk/core/curl_wrapper_types.h @@ -4,9 +4,9 @@ namespace mavsdk { -enum class Status { Idle = 0, Downloading = 1, Uploading = 2, Finished = 3, Error = 4 }; +enum class HttpStatus { Idle = 0, Downloading = 1, Uploading = 2, Finished = 3, Error = 4 }; -using ProgressCallback = std::function; +using ProgressCallback = std::function; struct UpProgress { int progress_in_percentage = 0; diff --git a/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp b/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp index 5325afb35..ae7c08868 100644 --- a/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp +++ b/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp @@ -296,13 +296,13 @@ void ComponentMetadataImpl::retrieve_metadata(uint8_t compid, COMP_METADATA_TYPE uri, tmp_download_path.string(), [this, &component, tmp_download_path, compid, type, file_cache_tag]( - int progress, Status status, CURLcode curl_code) -> int { + int progress, HttpStatus status, CURLcode curl_code) -> int { UNUSED(progress); - if (status == Status::Error) { + if (status == HttpStatus::Error) { LogErr() << "File download failed with result " << curl_code; // Move on to the next uri or type retrieve_metadata(compid, type); - } else if (status == Status::Finished) { + } else if (status == HttpStatus::Finished) { if (_verbose_debugging) { LogDebug() << "File download finished " << tmp_download_path; } From 300e0f524003b3a021b00f5f8b14aeaba19489fe Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 22 May 2024 15:41:01 +0200 Subject: [PATCH 3/9] core: add HandleFactory class Small wrapper to create unique ID's. Avoids the need for MavsdkImpl and CallbackListImpl to have private access to Handle. --- src/mavsdk/core/callback_list.h | 2 ++ src/mavsdk/core/callback_list_impl.h | 22 ++++++------- src/mavsdk/core/handle_factory.h | 41 +++++++++++++++++++++++++ src/mavsdk/core/include/mavsdk/handle.h | 12 +++----- src/mavsdk/core/mavsdk_impl.cpp | 2 +- src/mavsdk/core/mavsdk_impl.h | 4 +-- 6 files changed, 61 insertions(+), 22 deletions(-) create mode 100644 src/mavsdk/core/handle_factory.h diff --git a/src/mavsdk/core/callback_list.h b/src/mavsdk/core/callback_list.h index 1ab95fae9..cfb2737b2 100644 --- a/src/mavsdk/core/callback_list.h +++ b/src/mavsdk/core/callback_list.h @@ -10,6 +10,8 @@ namespace mavsdk { +template class CallbackListImpl; + template class CallbackList { public: CallbackList(); diff --git a/src/mavsdk/core/callback_list_impl.h b/src/mavsdk/core/callback_list_impl.h index 1bfe04ba4..7bd8c16c4 100644 --- a/src/mavsdk/core/callback_list_impl.h +++ b/src/mavsdk/core/callback_list_impl.h @@ -9,6 +9,7 @@ #include #include "log.h" #include "callback_list.h" +#include "handle_factory.h" namespace mavsdk { @@ -22,8 +23,7 @@ template class CallbackListImpl { // We need to return a handle, even if the callback is nullptr to // unsubscribe. That's fine, the handle just won't remove anything // when/if used later. - auto handleId = _last_id.fetch_add(1, std::memory_order_relaxed); - auto handle = Handle(handleId); + auto handle = _handle_factory.create(); if (callback != nullptr) { if (_mutex.try_lock()) { @@ -48,7 +48,7 @@ template class CallbackListImpl { void unsubscribe(Handle handle) { // Ignore null handle. - if (handle._id == 0) { + if (!handle.valid()) { LogErr() << "Invalid null handle"; return; } @@ -61,13 +61,11 @@ template class CallbackListImpl { if (lock.owns_lock()) { _list.erase( std::remove_if( - _list.begin(), - _list.end(), - [&](auto& pair) { return pair.first._id == handle._id; }), + _list.begin(), _list.end(), [&](auto& pair) { return pair.first == handle; }), _list.end()); } else { std::lock_guard remove_later_lock(_remove_later_mutex); - _remove_later.push_back(handle._id); + _remove_later.push_back(handle); } // check and remove from deferred lock list if present @@ -76,7 +74,7 @@ template class CallbackListImpl { std::remove_if( _subscribe_later.begin(), _subscribe_later.end(), - [&](const auto& pair) { return pair.first._id == handle._id; }), + [&](const auto& pair) { return pair.first == handle; }), _subscribe_later.end()); } @@ -172,12 +170,12 @@ template class CallbackListImpl { _remove_later.clear(); } - for (auto& id : _remove_later) { + for (const auto& handle : _remove_later) { _list.erase( std::remove_if( _list.begin(), _list.end(), - [&](auto& pair) { return pair.first._id == id; }), + [&](auto& pair) { return pair.first == handle; }), _list.end()); } _mutex.unlock(); @@ -215,12 +213,12 @@ template class CallbackListImpl { } mutable std::mutex _mutex{}; - std::atomic _last_id{1}; // Start at 1 because 0 is the "null handle" + HandleFactory _handle_factory; std::vector, std::function>> _list{}; std::vector> _cond_cb_list{}; mutable std::mutex _remove_later_mutex{}; - std::vector _remove_later{}; + std::vector> _remove_later{}; std::mutex _subscribe_later_mutex; std::vector, std::function>> _subscribe_later; diff --git a/src/mavsdk/core/handle_factory.h b/src/mavsdk/core/handle_factory.h new file mode 100644 index 000000000..3abe21b6a --- /dev/null +++ b/src/mavsdk/core/handle_factory.h @@ -0,0 +1,41 @@ +#pragma once + +#include "handle.h" +#include + +namespace mavsdk { + +/** + * @brief class to create unique Handle instances (thread-safe). + */ +template class HandleFactory { +public: + /** + * Create a new handle + */ + Handle create() + { + return Handle(_next_id.fetch_add(1, std::memory_order_relaxed)); + } + + /** + * Convert from another type of Handle into this one + */ + template Handle convert_from(const Handle& other) + { + return Handle(other._id); + } + + /** + * Convert from this type of Handle into another one + */ + template Handle convert_to(const Handle& other) + { + return Handle(other._id); + } + +private: + std::atomic_uint64_t _next_id{1}; ///< Start at 1 because 0 is the "null handle" +}; + +} // namespace mavsdk diff --git a/src/mavsdk/core/include/mavsdk/handle.h b/src/mavsdk/core/include/mavsdk/handle.h index c77396478..189513bd0 100644 --- a/src/mavsdk/core/include/mavsdk/handle.h +++ b/src/mavsdk/core/include/mavsdk/handle.h @@ -4,10 +4,8 @@ namespace mavsdk { -template class CallbackListImpl; -template class CallbackList; template class FakeHandle; -class MavsdkImpl; +template class HandleFactory; /** * @brief A handle returned from subscribe which allows to unsubscribe again. @@ -17,17 +15,17 @@ template class Handle { Handle() = default; ~Handle() = default; - bool operator<(const Handle& other) const { return _id < other._id; } + bool valid() const { return _id != 0; } -private: + bool operator<(const Handle& other) const { return _id < other._id; } bool operator==(const Handle& other) const { return _id == other._id; } +private: explicit Handle(uint64_t id) : _id(id) {} uint64_t _id{0}; - friend CallbackListImpl; friend FakeHandle; - friend MavsdkImpl; // For connections. + template friend class HandleFactory; }; } // namespace mavsdk diff --git a/src/mavsdk/core/mavsdk_impl.cpp b/src/mavsdk/core/mavsdk_impl.cpp index e7fc30b23..84977229d 100644 --- a/src/mavsdk/core/mavsdk_impl.cpp +++ b/src/mavsdk/core/mavsdk_impl.cpp @@ -619,7 +619,7 @@ Mavsdk::ConnectionHandle MavsdkImpl::add_connection(const std::shared_ptr& new_connection) { std::lock_guard lock(_connections_mutex); - auto handle = Mavsdk::ConnectionHandle{_connections_handle_id++}; + auto handle = _connections_handle_factory.create(); _connections.emplace_back(ConnectionEntry{new_connection, handle}); return handle; diff --git a/src/mavsdk/core/mavsdk_impl.h b/src/mavsdk/core/mavsdk_impl.h index c2f030361..40e2f49e0 100644 --- a/src/mavsdk/core/mavsdk_impl.h +++ b/src/mavsdk/core/mavsdk_impl.h @@ -11,7 +11,7 @@ #include "autopilot.h" #include "call_every_handler.h" #include "connection.h" -#include "handle.h" +#include "handle_factory.h" #include "mavsdk.h" #include "mavlink_include.h" #include "mavlink_address.h" @@ -135,7 +135,7 @@ class MavsdkImpl { static uint8_t get_target_component_id(const mavlink_message_t& message); std::mutex _connections_mutex{}; - uint64_t _connections_handle_id{1}; + HandleFactory<> _connections_handle_factory; struct ConnectionEntry { std::shared_ptr connection; Handle<> handle; From 1b74b54fd7633cf85fc0f514578eb84615e4581b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 22 May 2024 15:28:26 +0200 Subject: [PATCH 4/9] refactor component_metadata: move implementation to core This follows mavlink_ftp_client, so that other plugins can access component metadata as well. The Plugin API remains unchanged. --- src/mavsdk/core/CMakeLists.txt | 4 + .../file_cache.cpp | 0 .../component_metadata => core}/file_cache.h | 0 .../file_cache_test.cpp | 0 .../core/mavlink_component_metadata.cpp | 600 ++++++++++++++++ src/mavsdk/core/mavlink_component_metadata.h | 171 +++++ .../core/mavlink_component_metadata_test.cpp | 32 + src/mavsdk/core/system_impl.cpp | 3 +- src/mavsdk/core/system_impl.h | 12 +- .../plugins/component_metadata/CMakeLists.txt | 7 - .../component_metadata_impl.cpp | 659 ++---------------- .../component_metadata_impl.h | 125 +--- .../component_metadata_test.cpp | 32 - 13 files changed, 900 insertions(+), 745 deletions(-) rename src/mavsdk/{plugins/component_metadata => core}/file_cache.cpp (100%) rename src/mavsdk/{plugins/component_metadata => core}/file_cache.h (100%) rename src/mavsdk/{plugins/component_metadata => core}/file_cache_test.cpp (100%) create mode 100644 src/mavsdk/core/mavlink_component_metadata.cpp create mode 100644 src/mavsdk/core/mavlink_component_metadata.h create mode 100644 src/mavsdk/core/mavlink_component_metadata_test.cpp delete mode 100644 src/mavsdk/plugins/component_metadata/component_metadata_test.cpp diff --git a/src/mavsdk/core/CMakeLists.txt b/src/mavsdk/core/CMakeLists.txt index 5b6a41c2b..8b2a7729c 100644 --- a/src/mavsdk/core/CMakeLists.txt +++ b/src/mavsdk/core/CMakeLists.txt @@ -21,6 +21,7 @@ target_sources(mavsdk crc32.cpp system.cpp system_impl.cpp + file_cache.cpp flight_mode.cpp fs_utils.cpp inflate_lzma.cpp @@ -30,6 +31,7 @@ target_sources(mavsdk mavlink_channels.cpp mavlink_command_receiver.cpp mavlink_command_sender.cpp + mavlink_component_metadata.cpp mavlink_ftp_client.cpp mavlink_ftp_server.cpp mavlink_mission_transfer_client.cpp @@ -178,6 +180,7 @@ list(APPEND UNIT_TEST_SOURCES ${PROJECT_SOURCE_DIR}/mavsdk/core/callback_list_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/call_every_handler_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/cli_arg_test.cpp + ${PROJECT_SOURCE_DIR}/mavsdk/core/file_cache_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/locked_queue_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/geometry_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/math_conversions_test.cpp @@ -185,6 +188,7 @@ list(APPEND UNIT_TEST_SOURCES ${PROJECT_SOURCE_DIR}/mavsdk/core/mavsdk_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/mavsdk_time_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/mavlink_channels_test.cpp + ${PROJECT_SOURCE_DIR}/mavsdk/core/mavlink_component_metadata_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/mavlink_mission_transfer_client_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/mavlink_mission_transfer_server_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/mavlink_statustext_handler_test.cpp diff --git a/src/mavsdk/plugins/component_metadata/file_cache.cpp b/src/mavsdk/core/file_cache.cpp similarity index 100% rename from src/mavsdk/plugins/component_metadata/file_cache.cpp rename to src/mavsdk/core/file_cache.cpp diff --git a/src/mavsdk/plugins/component_metadata/file_cache.h b/src/mavsdk/core/file_cache.h similarity index 100% rename from src/mavsdk/plugins/component_metadata/file_cache.h rename to src/mavsdk/core/file_cache.h diff --git a/src/mavsdk/plugins/component_metadata/file_cache_test.cpp b/src/mavsdk/core/file_cache_test.cpp similarity index 100% rename from src/mavsdk/plugins/component_metadata/file_cache_test.cpp rename to src/mavsdk/core/file_cache_test.cpp diff --git a/src/mavsdk/core/mavlink_component_metadata.cpp b/src/mavsdk/core/mavlink_component_metadata.cpp new file mode 100644 index 000000000..23430fe4a --- /dev/null +++ b/src/mavsdk/core/mavlink_component_metadata.cpp @@ -0,0 +1,600 @@ +#include "mavlink_component_metadata.h" +#include "callback_list.tpp" +#include "fs_utils.h" +#include "inflate_lzma.h" +#include "unused.h" +#include "system_impl.h" + +#include +#include +#include +#include +#include + +#ifdef WINDOWS +#define strncasecmp(x, y, z) _strnicmp(x, y, z) +#endif + +namespace mavsdk { + +namespace fs = std::filesystem; + +MavlinkComponentMetadata::MavlinkComponentMetadata(SystemImpl& system_impl) : + _system_impl(system_impl) +{ + if (const char* env_p = std::getenv("MAVSDK_COMPONENT_METADATA_DEBUGGING")) { + if (std::string(env_p) == "1") { + LogDebug() << "Verbose component metadata logging is on"; + _verbose_debugging = true; + } + } + + const auto cache_dir_option = get_cache_directory(); + if (cache_dir_option) { + _file_cache.emplace( + cache_dir_option.value() / "component_metadata", 50, _verbose_debugging); + } else { + LogErr() << "Failed to get cache directory"; + } + + const auto tmp_option = create_tmp_directory("mavsdk-component-metadata"); + if (tmp_option) { + _tmp_download_path = tmp_option.value(); + } else { + _tmp_download_path = "./mavsdk-component-metadata"; + std::error_code err; + std::filesystem::create_directory(_tmp_download_path, err); + } +} + +MavlinkComponentMetadata::~MavlinkComponentMetadata() +{ + std::error_code ec; + std::filesystem::remove_all(_tmp_download_path, ec); + if (ec) { + LogErr() << "failed to remove directory: " << ec.message(); + } +} + +void MavlinkComponentMetadata::request_component(uint32_t compid) +{ + const std::lock_guard lg{_mavlink_components_mutex}; + if (_mavlink_components.find(compid) == _mavlink_components.end()) { + _mavlink_components[compid] = MavlinkComponent{}; + _system_impl.request_message().request( + MAVLINK_MSG_ID_COMPONENT_METADATA, compid, [this](auto&& result, auto&& message) { + receive_component_metadata(result, message); + }); + } +} + +void MavlinkComponentMetadata::receive_component_metadata( + MavlinkCommandSender::Result result, const mavlink_message_t& message) +{ + const std::lock_guard lg{_mavlink_components_mutex}; + if (_mavlink_components.find(message.compid) == _mavlink_components.end()) { + LogWarn() << "Unexpected component ID " << static_cast(message.compid); + return; + } + + // Store the result if the command failed + if (result != MavlinkCommandSender::Result::Success) { + switch (result) { + case MavlinkCommandSender::Result::ConnectionError: + _mavlink_components[message.compid].result = Result::ConnectionError; + break; + case MavlinkCommandSender::Result::Denied: + _mavlink_components[message.compid].result = Result::Denied; + break; + case MavlinkCommandSender::Result::Unsupported: + _mavlink_components[message.compid].result = Result::Unsupported; + break; + case MavlinkCommandSender::Result::Timeout: + _mavlink_components[message.compid].result = Result::Timeout; + break; + default: + _mavlink_components[message.compid].result = Result::Failed; + break; + } + LogWarn() << "Requesting component metadata failed with " << static_cast(result); + on_all_types_completed(message.compid); + return; + } + + mavlink_component_metadata_t component_metadata; + mavlink_msg_component_metadata_decode(&message, &component_metadata); + + component_metadata.uri[sizeof(component_metadata.uri) - 1] = '\0'; + _mavlink_components[message.compid].components.insert(std::make_pair( + COMP_METADATA_TYPE_GENERAL, + MetadataComponent{{component_metadata.uri, component_metadata.file_crc}})); + + retrieve_metadata(message.compid, COMP_METADATA_TYPE_GENERAL); +} + +std::string MavlinkComponentMetadata::get_file_cache_tag( + uint8_t compid, int comp_info_type, uint32_t crc, bool is_translation) +{ + char buf[255]; + snprintf( + buf, + sizeof(buf), + "compid-%03i_crc-%08x_type-%02i_trans-%i", + compid, + crc, + comp_info_type, + (int)is_translation); + return buf; +} +bool MavlinkComponentMetadata::uri_is_mavlinkftp( + const std::string& uri, std::string& download_path, uint8_t& target_compid) +{ + // Case insensitiv check if uri starts with "mftp://" + if (strncasecmp(uri.c_str(), "mftp://", 7) == 0) { + download_path = uri.substr(7); + // Extract optional [;comp=] prefix + std::regex compid_regex(R"(^(?:\[\;comp\=(\d+)\])(.*))"); + std::smatch match; + if (std::regex_search(download_path, match, compid_regex)) { + target_compid = std::stoi(match[1]); + download_path = match[2]; + } + return true; + } + return false; +} + +void MavlinkComponentMetadata::retrieve_metadata(uint8_t compid, COMP_METADATA_TYPE type) +{ + if (_verbose_debugging) { + LogDebug() << "MavlinkComponentMetadata::retrieve_metadata for compid " + << static_cast(compid) << ", type " << static_cast(type); + } + + const std::lock_guard lg{_mavlink_components_mutex}; + auto& component = _mavlink_components[compid].components[type]; + bool crc_valid; + uint32_t crc; + bool is_translation; + std::string uri; + + if (component.get_next_uri(crc_valid, crc, is_translation, uri)) { + // If translation locale is not set, skip translations + if (is_translation && !_translation_locale) { + retrieve_metadata(compid, type); + return; + } + + std::optional cached_file_option{}; + std::string file_cache_tag{}; + if (_file_cache && crc_valid) { + file_cache_tag = get_file_cache_tag(compid, type, crc, is_translation); + cached_file_option = _file_cache->access(file_cache_tag); + } + + if (cached_file_option) { + if (_verbose_debugging) { + LogDebug() << "Using cached file " << cached_file_option.value(); + } + component.current_metadata_path() = cached_file_option.value(); + retrieve_metadata(compid, type); + } else { + if (_verbose_debugging) { + LogDebug() << "Downloading json " << uri; + } + std::string download_path; + uint8_t target_compid = compid; + + if (uri_is_mavlinkftp(uri, download_path, target_compid)) { + // Create compid-specific tmp subdir, to ensure multiple components don't overwrite + // files from each other + const std::filesystem::path tmp_download_path = + _tmp_download_path / std::to_string(compid); + if (!std::filesystem::exists(tmp_download_path)) { + std::error_code err; + std::filesystem::create_directory(tmp_download_path, err); + } + + const std::filesystem::path local_path = + tmp_download_path / std::filesystem::path(download_path).filename(); + _system_impl.mavlink_ftp_client().download_async( + download_path, + tmp_download_path.string(), + true, + [this, &component, local_path, compid, type, file_cache_tag]( + MavlinkFtpClient::ClientResult download_result, + MavlinkFtpClient::ProgressData progress_data) { + if (download_result == MavlinkFtpClient::ClientResult::Next) { + if (_verbose_debugging) { + LogDebug() + << "File download progress: " << progress_data.bytes_transferred + << '/' << progress_data.total_bytes; + } + // TODO: detect slow link (e.g. telemetry), and cancel download + // (fallback to http) e.g. by estimating the remaining download time, + // and cancel if >40s + } else { + if (_verbose_debugging) { + LogDebug() << "File download ended with result " << download_result; + } + if (download_result == MavlinkFtpClient::ClientResult::Success) { + component.current_metadata_path() = + extract_and_cache_file(local_path, file_cache_tag); + } + // Move on to the next uri or type + retrieve_metadata(compid, type); + } + }, + target_compid); + + } else { + // http(s) download +#if BUILD_WITHOUT_CURL == 1 + LogErr() << "HTTP disabled at build time, skipping download of " << uri; + retrieve_metadata(compid, type); +#else + const std::string base_filename = filename_from_uri(uri); + const std::filesystem::path tmp_download_path = + _tmp_download_path / ("http-" + std::to_string(compid) + "-" + + std::to_string(type) + "-" + base_filename); + _http_loader.download_async( + uri, + tmp_download_path.string(), + [this, &component, tmp_download_path, compid, type, file_cache_tag]( + int progress, HttpStatus status, CURLcode curl_code) -> int { + UNUSED(progress); + if (status == HttpStatus::Error) { + LogErr() << "File download failed with result " << curl_code; + // Move on to the next uri or type + retrieve_metadata(compid, type); + } else if (status == HttpStatus::Finished) { + if (_verbose_debugging) { + LogDebug() << "File download finished " << tmp_download_path; + } + component.current_metadata_path() = + extract_and_cache_file(tmp_download_path, file_cache_tag); + // Move on to the next uri or type + retrieve_metadata(compid, type); + } + return 0; + }); +#endif + } + } + } else { + // Move on to next type + handle_metadata_type_completed(compid, type); + } +} + +void MavlinkComponentMetadata::handle_metadata_type_completed( + uint8_t compid, COMP_METADATA_TYPE type) +{ + const std::lock_guard lg{_mavlink_components_mutex}; + auto& component = _mavlink_components[compid].components[type]; + assert(component.is_completed()); + + // TODO: handle translations. For that we need to parse the translation summary json file + // component.json_translation() and then download the locale-specific translation file. + // See + // https://github.com/mavlink/qgroundcontrol/blob/master/src/Vehicle/ComponentInformationTranslation.cc + + if (type == COMP_METADATA_TYPE_GENERAL && component.json_metadata()) { + parse_component_metadata_general(compid, *component.json_metadata()); + } + + // Call user callbacks + if (component.json_metadata()) { + auto metadata_type = get_metadata_type(type); + if (metadata_type) { + const std::lock_guard lg_callbacks{_notification_callbacks_mutex}; + _notification_callbacks.queue( + MetadataUpdate{compid, metadata_type.value(), component.json_metadata().value()}, + [this](const auto& func) { _system_impl.call_user_callback(func); }); + } + } + + // Retrieve next remaining metadata type + bool all_completed = true; + for (const auto& [next_type, next_component] : _mavlink_components[compid].components) { + if (!next_component.is_completed()) { + retrieve_metadata(compid, next_type); + all_completed = false; + break; + } + } + if (all_completed) { + LogDebug() << "All metadata types completed for compid " << static_cast(compid); + _mavlink_components[compid].result = Result::Success; + on_all_types_completed(compid); + } +} + +std::optional MavlinkComponentMetadata::extract_and_cache_file( + const std::filesystem::path& path, const std::string& file_cache_tag) +{ + std::filesystem::path returned_path = path; + // Decompress if needed + if (path.extension() == ".lzma" || path.extension() == ".xz") { + returned_path.replace_extension(".extracted"); + if (InflateLZMA::inflateLZMAFile(path, returned_path)) { + std::filesystem::remove(path); + } else { + LogErr() << "Inflate of compressed json failed " << path; + return std::nullopt; + } + } + + if (_file_cache && !file_cache_tag.empty()) { + // Cache the file (this will move/remove the temp file as well) + returned_path = _file_cache->insert(file_cache_tag, returned_path).value_or(returned_path); + } + return returned_path; +} +std::string MavlinkComponentMetadata::filename_from_uri(const std::string& uri) +{ + // Extract the base name from an uri + const auto last_slash = uri.find_last_of('/'); + std::string base_filename = "downloaded_file.json"; + if (last_slash != std::string::npos) { + base_filename = uri.substr(last_slash + 1); + } + const auto parameter_index = base_filename.find('?'); + if (parameter_index != std::string::npos) { + base_filename = base_filename.substr(0, parameter_index); + } + return base_filename; +} +std::optional +MavlinkComponentMetadata::get_metadata_type(COMP_METADATA_TYPE type) +{ + switch (type) { + case COMP_METADATA_TYPE_PARAMETER: + return MetadataType::Parameter; + case COMP_METADATA_TYPE_EVENTS: + return MetadataType::Events; + case COMP_METADATA_TYPE_ACTUATORS: + return MetadataType::Actuators; + default: + break; + } + + return std::nullopt; +} +std::pair +MavlinkComponentMetadata::get_metadata(uint32_t compid, MetadataType type) +{ + COMP_METADATA_TYPE metadata_type{COMP_METADATA_TYPE_GENERAL}; + switch (type) { + case MetadataType::Parameter: + metadata_type = COMP_METADATA_TYPE_PARAMETER; + break; + case MetadataType::Events: + metadata_type = COMP_METADATA_TYPE_EVENTS; + break; + case MetadataType::Actuators: + metadata_type = COMP_METADATA_TYPE_ACTUATORS; + break; + case MetadataType::AllCompleted: + return std::make_pair(Result::Failed, MetadataData{}); + } + const std::lock_guard lg{_mavlink_components_mutex}; + const auto comp_iter = _mavlink_components.find(compid); + if (comp_iter != _mavlink_components.end()) { + const auto type_iter = comp_iter->second.components.find(metadata_type); + if (type_iter != comp_iter->second.components.end() && type_iter->second.json_metadata()) { + return std::make_pair( + Result::Success, MetadataData{*type_iter->second.json_metadata()}); + } + if (!comp_iter->second.result || *comp_iter->second.result == Result::Success) { + return std::make_pair(Result::NotAvailable, MetadataData{""}); + } else { + return std::make_pair(*comp_iter->second.result, MetadataData{""}); + } + } + return std::make_pair(Result::NotRequested, MetadataData{""}); +} +void MavlinkComponentMetadata::parse_component_metadata_general( + uint8_t compid, const std::string& json_metadata) +{ + Json::Value metadata; + Json::Reader reader; + bool parsing_successful = reader.parse(json_metadata, metadata); + if (!parsing_successful) { + LogErr() << "Failed to parse" << reader.getFormattedErrorMessages(); + return; + } + + if (!metadata.isMember("version")) { + LogErr() << "version not found"; + return; + } + + if (metadata["version"].asInt() != 1) { + LogWarn() << "version " << metadata["version"].asInt() << " not supported"; + return; + } + + if (!metadata.isMember("metadataTypes")) { + LogErr() << "metadataTypes not found"; + return; + } + + for (const auto& metadata_type : metadata["metadataTypes"]) { + if (!metadata_type.isMember("type")) { + LogErr() << "type missing"; + continue; + } + auto type = static_cast(metadata_type["type"].asInt()); + auto& components = _mavlink_components[compid].components; + if (components.find(type) != components.end()) { + LogErr() << "component type already added: " << type; + continue; + } + if (!metadata_type.isMember("uri")) { + LogErr() << "uri missing"; + continue; + } + + components.emplace(type, MetadataComponent{MetadataComponentUris{metadata_type}}); + } +} +void MavlinkComponentMetadata::unsubscribe_metadata_available(MetadataAvailableHandle handle) +{ + const std::lock_guard lg{_notification_callbacks_mutex}; + _notification_callbacks.unsubscribe(handle); +} +MavlinkComponentMetadata::MetadataAvailableHandle +MavlinkComponentMetadata::subscribe_metadata_available(const MetadataAvailableCallback& callback) +{ + const std::lock_guard lg_components{_mavlink_components_mutex}; // Take this mutex first + const std::lock_guard lg_callbacks{_notification_callbacks_mutex}; + const auto handle = _notification_callbacks.subscribe(callback); + + // Immediately call the callback for all already existing metadata (with the mutexes locked) + for (const auto& [compid, component] : _mavlink_components) { + for (const auto& [type, metadata] : component.components) { + auto metadata_type = get_metadata_type(type); + if (metadata.is_completed() && metadata.json_metadata() && metadata_type) { + _system_impl.call_user_callback([temp_callback = callback, + metadata_type = metadata_type.value(), + temp_compid = compid, + json_metadata = metadata.json_metadata().value()] { + temp_callback(MetadataUpdate{temp_compid, metadata_type, json_metadata}); + }); + } + } + if (component.result) { + _system_impl.call_user_callback([temp_callback = callback, temp_compid = compid] { + temp_callback(MetadataUpdate{temp_compid, MetadataType::AllCompleted, ""}); + }); + } + } + return handle; +} + +void MavlinkComponentMetadata::on_all_types_completed(uint8_t compid) +{ + const std::lock_guard lg_callbacks{_notification_callbacks_mutex}; + _notification_callbacks.queue( + MetadataUpdate{compid, MetadataType::AllCompleted, ""}, + [this](const auto& func) { _system_impl.call_user_callback(func); }); +} + +MetadataComponentUris::MetadataComponentUris(const Json::Value& value) +{ + if (value["uri"].isString()) { + _uri_metadata = value["uri"].asString(); + } + if (value["fileCrc"].isUInt()) { + _crc_metadata = value["fileCrc"].asUInt(); + _crc_metadata_valid = true; + } + if (value["uriFallback"].isString()) { + _uri_metadata_fallback = value["uriFallback"].asString(); + } + if (value["fileCrcFallback"].isUInt()) { + _crc_metadata_fallback = value["fileCrcFallback"].asUInt(); + _crc_metadata_fallback_valid = true; + } + if (value["translationUri"].isString()) { + _uri_translation = value["translationUri"].asString(); + } + if (value["translationUriFallback"].isString()) { + _uri_translation_fallback = value["translationUriFallback"].asString(); + } +} + +bool MetadataComponent::get_next_uri( + bool& crc_valid, uint32_t& crc, bool& is_translation, std::string& uri) +{ + // Skip fallback if we have valid data already + switch (_state) { + case State::Metadata: + if (_metadata) { + _state = State::MetadataFallback; + } + break; + case State::Translation: + if (_translation) { + _state = State::TranslationFallback; + } + break; + default: + break; + } + + uri = ""; + while (uri.empty() && _state != State::Done) { + switch (_state) { + case State::Init: + crc_valid = _metadata_uris.crc_meta_data_valid(); + crc = _metadata_uris.crc_meta_data(); + uri = _metadata_uris.uri_metadata(); + is_translation = false; + _state = State::Metadata; + break; + case State::Metadata: + crc_valid = _metadata_uris.crc_meta_data_fallback_valid(); + crc = _metadata_uris.crc_meta_data_fallback(); + uri = _metadata_uris.uri_metadata_fallback(); + is_translation = false; + _state = State::MetadataFallback; + break; + case State::MetadataFallback: + crc_valid = false; + crc = 0; + uri = _metadata_uris.uri_translation(); + is_translation = true; + _state = State::Translation; + break; + case State::Translation: + crc_valid = false; + crc = 0; + uri = _metadata_uris.uri_translation_fallback(); + is_translation = true; + _state = State::TranslationFallback; + break; + case State::TranslationFallback: + // Read files if available + if (_metadata) { + std::ifstream file(*_metadata); + if (file) { + std::stringstream buffer; + buffer << file.rdbuf(); + _json_metadata.emplace(buffer.str()); + } + } + if (_translation) { + std::ifstream file(*_translation); + if (file) { + std::stringstream buffer; + buffer << file.rdbuf(); + _json_translation.emplace(buffer.str()); + } + } + _state = State::Done; + break; + case State::Done: + break; + } + } + return _state != State::Done; +} +std::optional& MetadataComponent::current_metadata_path() +{ + switch (_state) { + case State::Metadata: + case State::MetadataFallback: + return _metadata; + case State::Translation: + case State::TranslationFallback: + return _translation; + case State::Done: + case State::Init: + break; + } + LogErr() << "current_metadata_path() called in invalid state"; + return _metadata; +} +} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_component_metadata.h b/src/mavsdk/core/mavlink_component_metadata.h new file mode 100644 index 000000000..132a507d3 --- /dev/null +++ b/src/mavsdk/core/mavlink_component_metadata.h @@ -0,0 +1,171 @@ +#pragma once + +#include "callback_list.h" +#include "file_cache.h" +#include "http_loader.h" +#include "mavlink_command_sender.h" +#include + +#include +#include +#include + +namespace mavsdk { + +class SystemImpl; + +class MetadataComponentUris { +public: + MetadataComponentUris() = default; + MetadataComponentUris(std::string metadata_uri, uint32_t metadata_crc) : + _crc_metadata_valid(true), + _crc_metadata(metadata_crc), + _uri_metadata(std::move(metadata_uri)) + {} + explicit MetadataComponentUris(const Json::Value& value); + + const std::string& uri_metadata() const { return _uri_metadata; } + const std::string& uri_metadata_fallback() const { return _uri_metadata_fallback; } + const std::string& uri_translation() const { return _uri_translation; } + const std::string& uri_translation_fallback() const { return _uri_translation_fallback; } + + uint32_t crc_meta_data() const { return _crc_metadata; } + uint32_t crc_meta_data_fallback() const { return _crc_metadata_fallback; } + bool crc_meta_data_valid() const { return _crc_metadata_valid; } + bool crc_meta_data_fallback_valid() const { return _crc_metadata_fallback_valid; } + + bool available() const { return !_uri_metadata.empty(); } + +private: + bool _crc_metadata_valid{false}; + bool _crc_metadata_fallback_valid{false}; + + uint32_t _crc_metadata{}; + uint32_t _crc_metadata_fallback{}; + + std::string _uri_metadata; + std::string _uri_metadata_fallback; + std::string _uri_translation; + std::string _uri_translation_fallback; +}; + +class MetadataComponent { +public: + MetadataComponent() : _metadata_uris() {} + explicit MetadataComponent(MetadataComponentUris metadata_uris) : + _metadata_uris(std::move(metadata_uris)) + {} + + bool get_next_uri(bool& crc_valid, uint32_t& crc, bool& is_translation, std::string& uri); + + std::optional& current_metadata_path(); + + bool is_completed() const { return _state == State::Done; } + + const std::optional& json_metadata() const { return _json_metadata; } + const std::optional& json_translation() const { return _json_translation; } + +private: + enum class State { + Init, + Metadata, + MetadataFallback, + Translation, + TranslationFallback, + Done, + }; + const MetadataComponentUris _metadata_uris; + + State _state{State::Init}; + std::optional _metadata; + std::optional _translation; + + std::optional _json_metadata; ///< the final json metadata + std::optional _json_translation; ///< the final json translation summary +}; + +class MavlinkComponentMetadata { +public: + explicit MavlinkComponentMetadata(SystemImpl& system_impl); + ~MavlinkComponentMetadata(); + + enum class MetadataType { + AllCompleted, /**< @brief This is set in the subscription callback when all metadata types + completed for a given component ID. */ + Parameter, /**< @brief Parameter metadata. */ + Events, /**< @brief Event definitions. */ + Actuators, /**< @brief Actuator definitions. */ + }; + struct MetadataData { + std::string json_metadata{}; /**< @brief The JSON metadata */ + }; + enum class Result { + Success, + NotAvailable, + ConnectionError, + Unsupported, + Denied, + Failed, + Timeout, + NoSystem, + NotRequested, + }; + struct MetadataUpdate { + uint32_t compid{}; /**< @brief The component ID */ + MetadataType type{}; /**< @brief The metadata type */ + std::string json_metadata{}; /**< @brief The JSON metadata */ + }; + using MetadataAvailableCallback = std::function; + using MetadataAvailableHandle = Handle; + + void request_component(uint32_t compid); + void request_autopilot_component() { request_component(MAV_COMP_ID_AUTOPILOT1); } + + std::pair get_metadata(uint32_t compid, MetadataType type); + + MetadataAvailableHandle subscribe_metadata_available(const MetadataAvailableCallback& callback); + void unsubscribe_metadata_available(MetadataAvailableHandle handle); + + static bool + uri_is_mavlinkftp(const std::string& uri, std::string& download_path, uint8_t& target_compid); + static std::string filename_from_uri(const std::string& uri); + +private: + struct MavlinkComponent { + std::map components; + std::optional result{}; ///< set once all types completed + }; + + void receive_component_metadata( + MavlinkCommandSender::Result result, const mavlink_message_t& message); + void retrieve_metadata(uint8_t compid, COMP_METADATA_TYPE type); + static std::string + get_file_cache_tag(uint8_t compid, int comp_info_type, uint32_t crc, bool is_translation); + std::optional + extract_and_cache_file(const std::filesystem::path& path, const std::string& file_cache_tag); + void on_all_types_completed(uint8_t compid); + + void handle_metadata_type_completed(uint8_t compid, COMP_METADATA_TYPE type); + void parse_component_metadata_general(uint8_t compid, const std::string& json_metadata); + + static std::optional get_metadata_type(COMP_METADATA_TYPE type); + + SystemImpl& _system_impl; + + std::mutex _notification_callbacks_mutex{}; ///< Protects access to _notification_callbacks + CallbackList _notification_callbacks; + + const std::optional + _translation_locale{}; ///< optional locale in the form of "language_country", e.g. de_DE + std::recursive_mutex _mavlink_components_mutex{}; ///< Protects access to _mavlink_components + std::map _mavlink_components{}; + std::optional _file_cache{}; + std::filesystem::path _tmp_download_path{}; + bool _verbose_debugging{false}; + +#if BUILD_WITHOUT_CURL != 1 + HttpLoader _http_loader; +#endif +}; + +} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_component_metadata_test.cpp b/src/mavsdk/core/mavlink_component_metadata_test.cpp new file mode 100644 index 000000000..ef5eab524 --- /dev/null +++ b/src/mavsdk/core/mavlink_component_metadata_test.cpp @@ -0,0 +1,32 @@ +#include "mavlink_component_metadata.h" + +#include + +using namespace mavsdk; + +TEST(MavlinkComponentMetadata, mavftp_uri) +{ + std::string download_path; + uint8_t compid = 3; + EXPECT_FALSE(MavlinkComponentMetadata::uri_is_mavlinkftp( + "http://url.com/file.json", download_path, compid)); + + EXPECT_TRUE( + MavlinkComponentMetadata::uri_is_mavlinkftp("mftp:///file.json", download_path, compid)); + EXPECT_EQ(compid, 3); + EXPECT_EQ(download_path, "/file.json"); + + EXPECT_TRUE(MavlinkComponentMetadata::uri_is_mavlinkftp( + "mftp://[;comp=39]/path/to/file.json", download_path, compid)); + EXPECT_EQ(compid, 39); + EXPECT_EQ(download_path, "/path/to/file.json"); +} + +TEST(MavlinkComponentMetadata, filename_from_uri) +{ + EXPECT_EQ( + MavlinkComponentMetadata::filename_from_uri("http://url.com/file.json.xz"), "file.json.xz"); + EXPECT_EQ( + MavlinkComponentMetadata::filename_from_uri("http://url.com/path/file.json?a=x&b=y"), + "file.json"); +} diff --git a/src/mavsdk/core/system_impl.cpp b/src/mavsdk/core/system_impl.cpp index 714170418..52e9added 100644 --- a/src/mavsdk/core/system_impl.cpp +++ b/src/mavsdk/core/system_impl.cpp @@ -34,7 +34,8 @@ SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) : [this]() { return autopilot(); }), _request_message( *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler), - _mavlink_ftp_client(*this) + _mavlink_ftp_client(*this), + _mavlink_component_metadata(*this) { _system_thread = new std::thread(&SystemImpl::system_thread, this); } diff --git a/src/mavsdk/core/system_impl.h b/src/mavsdk/core/system_impl.h index 930c79692..dd6a03e1a 100644 --- a/src/mavsdk/core/system_impl.h +++ b/src/mavsdk/core/system_impl.h @@ -2,6 +2,7 @@ #include "autopilot.h" #include "callback_list.h" +#include "mavlink_component_metadata.h" #include "call_every_handler.h" #include "flight_mode.h" #include "mavlink_address.h" @@ -271,7 +272,7 @@ class SystemImpl { bool is_connected() const; Time& get_time(); - AutopilotTime& get_autopilot_time() { return _autopilot_time; }; + AutopilotTime& get_autopilot_time() { return _autopilot_time; } double get_ping_time_s() const { return _ping.last_ping_time_s(); } @@ -283,11 +284,13 @@ class SystemImpl { void send_autopilot_version_request(); - MavlinkMissionTransferClient& mission_transfer_client() { return _mission_transfer_client; }; + MavlinkMissionTransferClient& mission_transfer_client() { return _mission_transfer_client; } - MavlinkFtpClient& mavlink_ftp_client() { return _mavlink_ftp_client; }; + MavlinkFtpClient& mavlink_ftp_client() { return _mavlink_ftp_client; } - RequestMessage& request_message() { return _request_message; }; + MavlinkComponentMetadata& component_metadata() { return _mavlink_component_metadata; } + + RequestMessage& request_message() { return _request_message; } // Non-copyable SystemImpl(const SystemImpl&) = delete; @@ -396,6 +399,7 @@ class SystemImpl { MavlinkMissionTransferClient _mission_transfer_client; RequestMessage _request_message; MavlinkFtpClient _mavlink_ftp_client; + MavlinkComponentMetadata _mavlink_component_metadata; std::mutex _plugin_impls_mutex{}; std::vector _plugin_impls{}; diff --git a/src/mavsdk/plugins/component_metadata/CMakeLists.txt b/src/mavsdk/plugins/component_metadata/CMakeLists.txt index 58332fbf3..4dc7358de 100644 --- a/src/mavsdk/plugins/component_metadata/CMakeLists.txt +++ b/src/mavsdk/plugins/component_metadata/CMakeLists.txt @@ -2,7 +2,6 @@ target_sources(mavsdk PRIVATE component_metadata.cpp component_metadata_impl.cpp - file_cache.cpp ) target_include_directories(mavsdk PUBLIC @@ -14,9 +13,3 @@ install(FILES include/plugins/component_metadata/component_metadata.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/mavsdk/plugins/component_metadata ) - -list(APPEND UNIT_TEST_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/file_cache_test.cpp - ${CMAKE_CURRENT_SOURCE_DIR}/component_metadata_test.cpp -) -set(UNIT_TEST_SOURCES ${UNIT_TEST_SOURCES} PARENT_SCOPE) diff --git a/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp b/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp index ae7c08868..fd4ee3b7a 100644 --- a/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp +++ b/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp @@ -1,18 +1,4 @@ #include "component_metadata_impl.h" -#include "callback_list.tpp" -#include "fs_utils.h" -#include "inflate_lzma.h" -#include "unused.h" - -#include -#include -#include -#include -#include - -#ifdef WINDOWS -#define strncasecmp(x, y, z) _strnicmp(x, y, z) -#endif namespace mavsdk { @@ -21,51 +7,17 @@ namespace fs = std::filesystem; ComponentMetadataImpl::ComponentMetadataImpl(System& system) : PluginImplBase(system) { _system_impl->register_plugin(this); - init_object(); } ComponentMetadataImpl::ComponentMetadataImpl(std::shared_ptr system) : PluginImplBase(std::move(system)) { _system_impl->register_plugin(this); - init_object(); -} - -void ComponentMetadataImpl::init_object() -{ - if (const char* env_p = std::getenv("MAVSDK_COMPONENT_METADATA_DEBUGGING")) { - if (std::string(env_p) == "1") { - LogDebug() << "Verbose component metadata logging is on"; - _verbose_debugging = true; - } - } - - const auto cache_dir_option = get_cache_directory(); - if (cache_dir_option) { - _file_cache.emplace( - cache_dir_option.value() / "component_metadata", 50, _verbose_debugging); - } else { - LogErr() << "Failed to get cache directory"; - } - - const auto tmp_option = create_tmp_directory("mavsdk-component-metadata"); - if (tmp_option) { - _tmp_download_path = tmp_option.value(); - } else { - _tmp_download_path = "./mavsdk-component-metadata"; - std::error_code err; - std::filesystem::create_directory(_tmp_download_path, err); - } } ComponentMetadataImpl::~ComponentMetadataImpl() { _system_impl->unregister_plugin(this); - std::error_code ec; - std::filesystem::remove_all(_tmp_download_path, ec); - if (ec) { - LogErr() << "failed to remove directory: " << ec.message(); - } } void ComponentMetadataImpl::init() {} @@ -74,592 +26,123 @@ void ComponentMetadataImpl::deinit() {} void ComponentMetadataImpl::enable() { - const std::lock_guard lg{_mavlink_components_mutex}; - _mavlink_components.clear(); + const std::lock_guard lg{_mutex}; request_componenents(); _is_enabled = true; } void ComponentMetadataImpl::disable() { - // TODO: stop ongoing downloads? _is_enabled = false; } void ComponentMetadataImpl::request_componenents() { - const std::lock_guard lg{_mavlink_components_mutex}; + // Assumes _mutex is taken for (const auto& component : _components_to_request) { - if (_mavlink_components.find(component) == _mavlink_components.end()) { - _mavlink_components[component] = MavlinkComponent{}; - _system_impl->request_message().request( - MAVLINK_MSG_ID_COMPONENT_METADATA, - component, - [this](auto&& result, auto&& message) { - receive_component_metadata(result, message); - }); - } + _system_impl->component_metadata().request_component(component); } } void ComponentMetadataImpl::request_component(uint32_t compid) { + const std::lock_guard lg{_mutex}; _components_to_request.insert(compid); if (_is_enabled) { request_componenents(); } } -void ComponentMetadataImpl::receive_component_metadata( - MavlinkCommandSender::Result result, const mavlink_message_t& message) -{ - const std::lock_guard lg{_mavlink_components_mutex}; - if (_mavlink_components.find(message.compid) == _mavlink_components.end()) { - LogWarn() << "Unexpected component ID " << static_cast(message.compid); - return; - } - - // Store the result if the command failed - if (result != MavlinkCommandSender::Result::Success) { - switch (result) { - case MavlinkCommandSender::Result::ConnectionError: - _mavlink_components[message.compid].result = - ComponentMetadata::Result::ConnectionError; - break; - case MavlinkCommandSender::Result::Denied: - _mavlink_components[message.compid].result = ComponentMetadata::Result::Denied; - break; - case MavlinkCommandSender::Result::Unsupported: - _mavlink_components[message.compid].result = ComponentMetadata::Result::Unsupported; - break; - case MavlinkCommandSender::Result::Timeout: - _mavlink_components[message.compid].result = ComponentMetadata::Result::Timeout; - break; - default: - _mavlink_components[message.compid].result = ComponentMetadata::Result::Failed; - break; - } - LogWarn() << "Requesting component metadata failed with " << static_cast(result); - on_all_types_completed(message.compid); - return; - } - - mavlink_component_metadata_t component_metadata; - mavlink_msg_component_metadata_decode(&message, &component_metadata); - - component_metadata.uri[sizeof(component_metadata.uri) - 1] = '\0'; - _mavlink_components[message.compid].components.insert(std::make_pair( - COMP_METADATA_TYPE_GENERAL, - MetadataComponent{{component_metadata.uri, component_metadata.file_crc}})); - - retrieve_metadata(message.compid, COMP_METADATA_TYPE_GENERAL); -} - -std::string ComponentMetadataImpl::get_file_cache_tag( - uint8_t compid, int comp_info_type, uint32_t crc, bool is_translation) -{ - char buf[255]; - snprintf( - buf, - sizeof(buf), - "compid-%03i_crc-%08x_type-%02i_trans-%i", - compid, - crc, - comp_info_type, - (int)is_translation); - return buf; -} -bool ComponentMetadataImpl::uri_is_mavlinkftp( - const std::string& uri, std::string& download_path, uint8_t& target_compid) -{ - // Case insensitiv check if uri starts with "mftp://" - if (strncasecmp(uri.c_str(), "mftp://", 7) == 0) { - download_path = uri.substr(7); - // Extract optional [;comp=] prefix - std::regex compid_regex(R"(^(?:\[\;comp\=(\d+)\])(.*))"); - std::smatch match; - if (std::regex_search(download_path, match, compid_regex)) { - target_compid = std::stoi(match[1]); - download_path = match[2]; - } - return true; - } - return false; -} - -void ComponentMetadataImpl::retrieve_metadata(uint8_t compid, COMP_METADATA_TYPE type) +std::pair +ComponentMetadataImpl::get_metadata(uint32_t compid, ComponentMetadata::MetadataType type) { - if (_verbose_debugging) { - LogDebug() << "ComponentMetadataImpl::retrieve_metadata for compid " - << static_cast(compid) << ", type " << static_cast(type); - } - - const std::lock_guard lg{_mavlink_components_mutex}; - auto& component = _mavlink_components[compid].components[type]; - bool crc_valid; - uint32_t crc; - bool is_translation; - std::string uri; - - if (component.get_next_uri(crc_valid, crc, is_translation, uri)) { - // If translation locale is not set, skip translations - if (is_translation && !_translation_locale) { - retrieve_metadata(compid, type); - return; - } - - std::optional cached_file_option{}; - std::string file_cache_tag{}; - if (_file_cache && crc_valid) { - file_cache_tag = get_file_cache_tag(compid, type, crc, is_translation); - cached_file_option = _file_cache->access(file_cache_tag); - } - - if (cached_file_option) { - if (_verbose_debugging) { - LogDebug() << "Using cached file " << cached_file_option.value(); - } - component.current_metadata_path() = cached_file_option.value(); - retrieve_metadata(compid, type); - } else { - if (_verbose_debugging) { - LogDebug() << "Downloading json " << uri; - } - std::string download_path; - uint8_t target_compid = compid; - - if (uri_is_mavlinkftp(uri, download_path, target_compid)) { - // Create compid-specific tmp subdir, to ensure multiple components don't overwrite - // files from each other - const std::filesystem::path tmp_download_path = - _tmp_download_path / std::to_string(compid); - if (!std::filesystem::exists(tmp_download_path)) { - std::error_code err; - std::filesystem::create_directory(tmp_download_path, err); - } - - const std::filesystem::path local_path = - tmp_download_path / std::filesystem::path(download_path).filename(); - - _system_impl->call_user_callback([this, - download_path, - tmp_download_path, - &component, - target_compid, - local_path, - compid, - type, - file_cache_tag]() { - _system_impl->mavlink_ftp_client().download_async( - download_path, - tmp_download_path.string(), - true, - [this, &component, local_path, compid, type, file_cache_tag]( - MavlinkFtpClient::ClientResult download_result, - MavlinkFtpClient::ProgressData progress_data) { - if (download_result == MavlinkFtpClient::ClientResult::Next) { - if (_verbose_debugging) { - LogDebug() << "File download progress: " - << progress_data.bytes_transferred << '/' - << progress_data.total_bytes; - } - // TODO: detect slow link (e.g. telemetry), and cancel download - // (fallback to http) e.g. by estimating the remaining download - // time, and cancel if >40s - } else { - if (_verbose_debugging) { - LogDebug() - << "File download ended with result " << download_result; - } - if (download_result == MavlinkFtpClient::ClientResult::Success) { - component.current_metadata_path() = - extract_and_cache_file(local_path, file_cache_tag); - } - // Move on to the next uri or type - retrieve_metadata(compid, type); - } - }, - target_compid); - }); - - } else { - // http(s) download -#if BUILD_WITHOUT_CURL == 1 - LogErr() << "HTTP disabled at build time, skipping download of " << uri; - retrieve_metadata(compid, type); -#else - const std::string base_filename = filename_from_uri(uri); - const std::filesystem::path tmp_download_path = - _tmp_download_path / ("http-" + std::to_string(compid) + "-" + - std::to_string(type) + "-" + base_filename); - _http_loader.download_async( - uri, - tmp_download_path.string(), - [this, &component, tmp_download_path, compid, type, file_cache_tag]( - int progress, HttpStatus status, CURLcode curl_code) -> int { - UNUSED(progress); - if (status == HttpStatus::Error) { - LogErr() << "File download failed with result " << curl_code; - // Move on to the next uri or type - retrieve_metadata(compid, type); - } else if (status == HttpStatus::Finished) { - if (_verbose_debugging) { - LogDebug() << "File download finished " << tmp_download_path; - } - component.current_metadata_path() = - extract_and_cache_file(tmp_download_path, file_cache_tag); - // Move on to the next uri or type - retrieve_metadata(compid, type); - } - return 0; - }); -#endif - } - } - } else { - // Move on to next type - handle_metadata_type_completed(compid, type); - } + auto result = + _system_impl->component_metadata().get_metadata(compid, convert_metadata_type(type)); + return std::make_pair( + convert_result(result.first), convert_metadata_data(std::move(result.second))); } -void ComponentMetadataImpl::handle_metadata_type_completed(uint8_t compid, COMP_METADATA_TYPE type) +void ComponentMetadataImpl::unsubscribe_metadata_available( + ComponentMetadata::MetadataAvailableHandle handle) { - const std::lock_guard lg{_mavlink_components_mutex}; - auto& component = _mavlink_components[compid].components[type]; - assert(component.is_completed()); - - // TODO: handle translations. For that we need to parse the translation summary json file - // component.json_translation() and then download the locale-specific translation file. - // See - // https://github.com/mavlink/qgroundcontrol/blob/master/src/Vehicle/ComponentInformationTranslation.cc - - if (type == COMP_METADATA_TYPE_GENERAL && component.json_metadata()) { - parse_component_metadata_general(compid, *component.json_metadata()); - } - - // Call user callbacks - if (component.json_metadata()) { - auto metadata_type = get_metadata_type(type); - if (metadata_type) { - const std::lock_guard lg_callbacks{_notification_callbacks_mutex}; - _notification_callbacks.queue( - ComponentMetadata::MetadataUpdate{ - compid, metadata_type.value(), component.json_metadata().value()}, - [this](const auto& func) { _system_impl->call_user_callback(func); }); - } - } - - // Retrieve next remaining metadata type - bool all_completed = true; - for (const auto& [next_type, next_component] : _mavlink_components[compid].components) { - if (!next_component.is_completed()) { - retrieve_metadata(compid, next_type); - all_completed = false; - break; - } - } - if (all_completed) { - LogDebug() << "All metadata types completed for compid " << static_cast(compid); - _mavlink_components[compid].result = ComponentMetadata::Result::Success; - on_all_types_completed(compid); - } + const auto converted_handle = + _handle_factory.convert_to(handle); + _system_impl->component_metadata().unsubscribe_metadata_available(converted_handle); } - -std::optional ComponentMetadataImpl::extract_and_cache_file( - const std::filesystem::path& path, const std::string& file_cache_tag) -{ - std::filesystem::path returned_path = path; - // Decompress if needed - if (path.extension() == ".lzma" || path.extension() == ".xz") { - returned_path.replace_extension(".extracted"); - if (InflateLZMA::inflateLZMAFile(path, returned_path)) { - std::filesystem::remove(path); - } else { - LogErr() << "Inflate of compressed json failed " << path; - return std::nullopt; - } - } - - if (_file_cache && !file_cache_tag.empty()) { - // Cache the file (this will move/remove the temp file as well) - returned_path = _file_cache->insert(file_cache_tag, returned_path).value_or(returned_path); - } - return returned_path; -} -std::string ComponentMetadataImpl::filename_from_uri(const std::string& uri) +ComponentMetadata::MetadataAvailableHandle ComponentMetadataImpl::subscribe_metadata_available( + const ComponentMetadata::MetadataAvailableCallback& callback) { - // Extract the base name from an uri - const auto last_slash = uri.find_last_of('/'); - std::string base_filename = "downloaded_file.json"; - if (last_slash != std::string::npos) { - base_filename = uri.substr(last_slash + 1); - } - const auto parameter_index = base_filename.find('?'); - if (parameter_index != std::string::npos) { - base_filename = base_filename.substr(0, parameter_index); - } - return base_filename; -} -std::optional -ComponentMetadataImpl::get_metadata_type(COMP_METADATA_TYPE type) + const auto handle = _system_impl->component_metadata().subscribe_metadata_available( + [temp_callback = callback](MavlinkComponentMetadata::MetadataUpdate update) { + temp_callback(convert_metadata_update(std::move(update))); + }); + return _handle_factory.convert_from(handle); +} +ComponentMetadata::Result +ComponentMetadataImpl::convert_result(MavlinkComponentMetadata::Result result) +{ + switch (result) { + case MavlinkComponentMetadata::Result::Success: + return ComponentMetadata::Result::Success; + case MavlinkComponentMetadata::Result::NotAvailable: + return ComponentMetadata::Result::NotAvailable; + case MavlinkComponentMetadata::Result::ConnectionError: + return ComponentMetadata::Result::ConnectionError; + case MavlinkComponentMetadata::Result::Unsupported: + return ComponentMetadata::Result::Unsupported; + case MavlinkComponentMetadata::Result::Denied: + return ComponentMetadata::Result::Denied; + case MavlinkComponentMetadata::Result::Failed: + return ComponentMetadata::Result::Failed; + case MavlinkComponentMetadata::Result::Timeout: + return ComponentMetadata::Result::Timeout; + case MavlinkComponentMetadata::Result::NoSystem: + return ComponentMetadata::Result::NoSystem; + case MavlinkComponentMetadata::Result::NotRequested: + return ComponentMetadata::Result::NotRequested; + } + return ComponentMetadata::Result::Failed; +} +ComponentMetadata::MetadataType +ComponentMetadataImpl::convert_metadata_type(MavlinkComponentMetadata::MetadataType type) { switch (type) { - case COMP_METADATA_TYPE_PARAMETER: + case MavlinkComponentMetadata::MetadataType::AllCompleted: + return ComponentMetadata::MetadataType::AllCompleted; + case MavlinkComponentMetadata::MetadataType::Parameter: return ComponentMetadata::MetadataType::Parameter; - case COMP_METADATA_TYPE_EVENTS: + case MavlinkComponentMetadata::MetadataType::Events: return ComponentMetadata::MetadataType::Events; - case COMP_METADATA_TYPE_ACTUATORS: + case MavlinkComponentMetadata::MetadataType::Actuators: return ComponentMetadata::MetadataType::Actuators; - default: - break; } - - return std::nullopt; + return ComponentMetadata::MetadataType::Parameter; } -std::pair -ComponentMetadataImpl::get_metadata(uint32_t compid, ComponentMetadata::MetadataType type) +MavlinkComponentMetadata::MetadataType +ComponentMetadataImpl::convert_metadata_type(ComponentMetadata::MetadataType type) { - COMP_METADATA_TYPE metadata_type{COMP_METADATA_TYPE_GENERAL}; switch (type) { + case ComponentMetadata::MetadataType::AllCompleted: + return MavlinkComponentMetadata::MetadataType::AllCompleted; case ComponentMetadata::MetadataType::Parameter: - metadata_type = COMP_METADATA_TYPE_PARAMETER; - break; + return MavlinkComponentMetadata::MetadataType::Parameter; case ComponentMetadata::MetadataType::Events: - metadata_type = COMP_METADATA_TYPE_EVENTS; - break; + return MavlinkComponentMetadata::MetadataType::Events; case ComponentMetadata::MetadataType::Actuators: - metadata_type = COMP_METADATA_TYPE_ACTUATORS; - break; - case ComponentMetadata::MetadataType::AllCompleted: - return std::make_pair( - ComponentMetadata::Result::Failed, ComponentMetadata::MetadataData{}); - } - const std::lock_guard lg{_mavlink_components_mutex}; - const auto comp_iter = _mavlink_components.find(compid); - if (comp_iter != _mavlink_components.end()) { - const auto type_iter = comp_iter->second.components.find(metadata_type); - if (type_iter != comp_iter->second.components.end() && type_iter->second.json_metadata()) { - return std::make_pair( - ComponentMetadata::Result::Success, - ComponentMetadata::MetadataData{*type_iter->second.json_metadata()}); - } - if (!comp_iter->second.result || - *comp_iter->second.result == ComponentMetadata::Result::Success) { - return std::make_pair( - ComponentMetadata::Result::NotAvailable, ComponentMetadata::MetadataData{""}); - } else { - return std::make_pair(*comp_iter->second.result, ComponentMetadata::MetadataData{""}); - } - } - return std::make_pair( - ComponentMetadata::Result::NotRequested, ComponentMetadata::MetadataData{""}); -} -void ComponentMetadataImpl::parse_component_metadata_general( - uint8_t compid, const std::string& json_metadata) -{ - Json::Value metadata; - Json::Reader reader; - bool parsing_successful = reader.parse(json_metadata, metadata); - if (!parsing_successful) { - LogErr() << "Failed to parse" << reader.getFormattedErrorMessages(); - return; - } - - if (!metadata.isMember("version")) { - LogErr() << "version not found"; - return; - } - - if (metadata["version"].asInt() != 1) { - LogWarn() << "version " << metadata["version"].asInt() << " not supported"; - return; - } - - if (!metadata.isMember("metadataTypes")) { - LogErr() << "metadataTypes not found"; - return; - } - - for (const auto& metadata_type : metadata["metadataTypes"]) { - if (!metadata_type.isMember("type")) { - LogErr() << "type missing"; - continue; - } - auto type = static_cast(metadata_type["type"].asInt()); - auto& components = _mavlink_components[compid].components; - if (components.find(type) != components.end()) { - LogErr() << "component type already added: " << type; - continue; - } - if (!metadata_type.isMember("uri")) { - LogErr() << "uri missing"; - continue; - } - - components.emplace(type, MetadataComponent{MetadataComponentUris{metadata_type}}); + return MavlinkComponentMetadata::MetadataType::Actuators; } + return MavlinkComponentMetadata::MetadataType::Parameter; } -void ComponentMetadataImpl::unsubscribe_metadata_available( - ComponentMetadata::MetadataAvailableHandle handle) +ComponentMetadata::MetadataData +ComponentMetadataImpl::convert_metadata_data(MavlinkComponentMetadata::MetadataData data) { - const std::lock_guard lg{_notification_callbacks_mutex}; - _notification_callbacks.unsubscribe(handle); + return ComponentMetadata::MetadataData{std::move(data.json_metadata)}; } -ComponentMetadata::MetadataAvailableHandle ComponentMetadataImpl::subscribe_metadata_available( - const ComponentMetadata::MetadataAvailableCallback& callback) +ComponentMetadata::MetadataUpdate +ComponentMetadataImpl::convert_metadata_update(MavlinkComponentMetadata::MetadataUpdate data) { - const std::lock_guard lg_components{_mavlink_components_mutex}; // Take this mutex first - const std::lock_guard lg_callbacks{_notification_callbacks_mutex}; - const auto handle = _notification_callbacks.subscribe(callback); - - // Immediately call the callback for all already existing metadata (with the mutexes locked) - for (const auto& [compid, component] : _mavlink_components) { - for (const auto& [type, metadata] : component.components) { - auto metadata_type = get_metadata_type(type); - if (metadata.is_completed() && metadata.json_metadata() && metadata_type) { - _system_impl->call_user_callback( - [temp_callback = callback, - metadata_type = metadata_type.value(), - temp_compid = compid, - json_metadata = metadata.json_metadata().value()] { - temp_callback(ComponentMetadata::MetadataUpdate{ - temp_compid, metadata_type, json_metadata}); - }); - } - } - if (component.result) { - _system_impl->call_user_callback([temp_callback = callback, temp_compid = compid] { - temp_callback(ComponentMetadata::MetadataUpdate{ - temp_compid, ComponentMetadata::MetadataType::AllCompleted, ""}); - }); - } - } - return handle; -} - -void ComponentMetadataImpl::on_all_types_completed(uint8_t compid) -{ - const std::lock_guard lg_callbacks{_notification_callbacks_mutex}; - _notification_callbacks.queue( - ComponentMetadata::MetadataUpdate{ - compid, ComponentMetadata::MetadataType::AllCompleted, ""}, - [this](const auto& func) { _system_impl->call_user_callback(func); }); -} - -MetadataComponentUris::MetadataComponentUris(const Json::Value& value) -{ - if (value["uri"].isString()) { - _uri_metadata = value["uri"].asString(); - } - if (value["fileCrc"].isUInt()) { - _crc_metadata = value["fileCrc"].asUInt(); - _crc_metadata_valid = true; - } - if (value["uriFallback"].isString()) { - _uri_metadata_fallback = value["uriFallback"].asString(); - } - if (value["fileCrcFallback"].isUInt()) { - _crc_metadata_fallback = value["fileCrcFallback"].asUInt(); - _crc_metadata_fallback_valid = true; - } - if (value["translationUri"].isString()) { - _uri_translation = value["translationUri"].asString(); - } - if (value["translationUriFallback"].isString()) { - _uri_translation_fallback = value["translationUriFallback"].asString(); - } + return ComponentMetadata::MetadataUpdate{ + data.compid, convert_metadata_type(data.type), std::move(data.json_metadata)}; } -bool MetadataComponent::get_next_uri( - bool& crc_valid, uint32_t& crc, bool& is_translation, std::string& uri) -{ - // Skip fallback if we have valid data already - switch (_state) { - case State::Metadata: - if (_metadata) { - _state = State::MetadataFallback; - } - break; - case State::Translation: - if (_translation) { - _state = State::TranslationFallback; - } - break; - default: - break; - } - - uri = ""; - while (uri.empty() && _state != State::Done) { - switch (_state) { - case State::Init: - crc_valid = _metadata_uris.crc_meta_data_valid(); - crc = _metadata_uris.crc_meta_data(); - uri = _metadata_uris.uri_metadata(); - is_translation = false; - _state = State::Metadata; - break; - case State::Metadata: - crc_valid = _metadata_uris.crc_meta_data_fallback_valid(); - crc = _metadata_uris.crc_meta_data_fallback(); - uri = _metadata_uris.uri_metadata_fallback(); - is_translation = false; - _state = State::MetadataFallback; - break; - case State::MetadataFallback: - crc_valid = false; - crc = 0; - uri = _metadata_uris.uri_translation(); - is_translation = true; - _state = State::Translation; - break; - case State::Translation: - crc_valid = false; - crc = 0; - uri = _metadata_uris.uri_translation_fallback(); - is_translation = true; - _state = State::TranslationFallback; - break; - case State::TranslationFallback: - // Read files if available - if (_metadata) { - std::ifstream file(*_metadata); - if (file) { - std::stringstream buffer; - buffer << file.rdbuf(); - _json_metadata.emplace(buffer.str()); - } - } - if (_translation) { - std::ifstream file(*_translation); - if (file) { - std::stringstream buffer; - buffer << file.rdbuf(); - _json_translation.emplace(buffer.str()); - } - } - _state = State::Done; - break; - case State::Done: - break; - } - } - return _state != State::Done; -} -std::optional& MetadataComponent::current_metadata_path() -{ - switch (_state) { - case State::Metadata: - case State::MetadataFallback: - return _metadata; - case State::Translation: - case State::TranslationFallback: - return _translation; - case State::Done: - case State::Init: - break; - } - LogErr() << "current_metadata_path() called in invalid state"; - return _metadata; -} } // namespace mavsdk diff --git a/src/mavsdk/plugins/component_metadata/component_metadata_impl.h b/src/mavsdk/plugins/component_metadata/component_metadata_impl.h index bb7d28277..a0ca4ad9a 100644 --- a/src/mavsdk/plugins/component_metadata/component_metadata_impl.h +++ b/src/mavsdk/plugins/component_metadata/component_metadata_impl.h @@ -2,87 +2,12 @@ #include "plugins/component_metadata/component_metadata.h" #include "plugin_impl_base.h" -#include "callback_list.h" -#include "file_cache.h" -#include "http_loader.h" -#include +#include "handle_factory.h" -#include #include -#include namespace mavsdk { -class MetadataComponentUris { -public: - MetadataComponentUris() = default; - MetadataComponentUris(std::string metadata_uri, uint32_t metadata_crc) : - _crc_metadata_valid(true), - _crc_metadata(metadata_crc), - _uri_metadata(std::move(metadata_uri)) - {} - explicit MetadataComponentUris(const Json::Value& value); - - const std::string& uri_metadata() const { return _uri_metadata; } - const std::string& uri_metadata_fallback() const { return _uri_metadata_fallback; } - const std::string& uri_translation() const { return _uri_translation; } - const std::string& uri_translation_fallback() const { return _uri_translation_fallback; } - - uint32_t crc_meta_data() const { return _crc_metadata; } - uint32_t crc_meta_data_fallback() const { return _crc_metadata_fallback; } - bool crc_meta_data_valid() const { return _crc_metadata_valid; } - bool crc_meta_data_fallback_valid() const { return _crc_metadata_fallback_valid; } - - bool available() const { return !_uri_metadata.empty(); } - -private: - bool _crc_metadata_valid{false}; - bool _crc_metadata_fallback_valid{false}; - - uint32_t _crc_metadata{}; - uint32_t _crc_metadata_fallback{}; - - std::string _uri_metadata; - std::string _uri_metadata_fallback; - std::string _uri_translation; - std::string _uri_translation_fallback; -}; - -class MetadataComponent { -public: - MetadataComponent() : _metadata_uris() {} - explicit MetadataComponent(MetadataComponentUris metadata_uris) : - _metadata_uris(std::move(metadata_uris)) - {} - - bool get_next_uri(bool& crc_valid, uint32_t& crc, bool& is_translation, std::string& uri); - - std::optional& current_metadata_path(); - - bool is_completed() const { return _state == State::Done; } - - const std::optional& json_metadata() const { return _json_metadata; } - const std::optional& json_translation() const { return _json_translation; } - -private: - enum class State { - Init, - Metadata, - MetadataFallback, - Translation, - TranslationFallback, - Done, - }; - const MetadataComponentUris _metadata_uris; - - State _state{State::Init}; - std::optional _metadata; - std::optional _translation; - - std::optional _json_metadata; ///< the final json metadata - std::optional _json_translation; ///< the final json translation summary -}; - class ComponentMetadataImpl : public PluginImplBase { public: explicit ComponentMetadataImpl(System& system); @@ -105,50 +30,24 @@ class ComponentMetadataImpl : public PluginImplBase { subscribe_metadata_available(const ComponentMetadata::MetadataAvailableCallback& callback); void unsubscribe_metadata_available(ComponentMetadata::MetadataAvailableHandle handle); - static bool - uri_is_mavlinkftp(const std::string& uri, std::string& download_path, uint8_t& target_compid); - static std::string filename_from_uri(const std::string& uri); - private: - struct MavlinkComponent { - std::map components; - std::optional result{}; ///< set once all types completed - }; - - void init_object(); - void receive_component_metadata( - MavlinkCommandSender::Result result, const mavlink_message_t& message); - void retrieve_metadata(uint8_t compid, COMP_METADATA_TYPE type); - static std::string - get_file_cache_tag(uint8_t compid, int comp_info_type, uint32_t crc, bool is_translation); - std::optional - extract_and_cache_file(const std::filesystem::path& path, const std::string& file_cache_tag); void request_componenents(); - void on_all_types_completed(uint8_t compid); - void handle_metadata_type_completed(uint8_t compid, COMP_METADATA_TYPE type); - void parse_component_metadata_general(uint8_t compid, const std::string& json_metadata); - - static std::optional - get_metadata_type(COMP_METADATA_TYPE type); + static ComponentMetadata::Result convert_result(MavlinkComponentMetadata::Result result); + static ComponentMetadata::MetadataType + convert_metadata_type(MavlinkComponentMetadata::MetadataType type); + static MavlinkComponentMetadata::MetadataType + convert_metadata_type(ComponentMetadata::MetadataType type); + static ComponentMetadata::MetadataData + convert_metadata_data(MavlinkComponentMetadata::MetadataData data); + static ComponentMetadata::MetadataUpdate + convert_metadata_update(MavlinkComponentMetadata::MetadataUpdate data); std::set _components_to_request; bool _is_enabled{false}; + std::mutex _mutex{}; - std::mutex _notification_callbacks_mutex{}; ///< Protects access to _notification_callbacks - CallbackList _notification_callbacks; - - const std::optional - _translation_locale{}; ///< optional locale in the form of "language_country", e.g. de_DE - std::recursive_mutex _mavlink_components_mutex{}; ///< Protects access to _mavlink_components - std::map _mavlink_components{}; - std::optional _file_cache{}; - std::filesystem::path _tmp_download_path{}; - bool _verbose_debugging{false}; - -#if BUILD_WITHOUT_CURL != 1 - HttpLoader _http_loader; -#endif + HandleFactory _handle_factory; }; } // namespace mavsdk diff --git a/src/mavsdk/plugins/component_metadata/component_metadata_test.cpp b/src/mavsdk/plugins/component_metadata/component_metadata_test.cpp deleted file mode 100644 index bbebca246..000000000 --- a/src/mavsdk/plugins/component_metadata/component_metadata_test.cpp +++ /dev/null @@ -1,32 +0,0 @@ -#include "component_metadata_impl.h" - -#include - -using namespace mavsdk; - -TEST(ComponentMetadata, mavftp_uri) -{ - std::string download_path; - uint8_t compid = 3; - EXPECT_FALSE(ComponentMetadataImpl::uri_is_mavlinkftp( - "http://url.com/file.json", download_path, compid)); - - EXPECT_TRUE( - ComponentMetadataImpl::uri_is_mavlinkftp("mftp:///file.json", download_path, compid)); - EXPECT_EQ(compid, 3); - EXPECT_EQ(download_path, "/file.json"); - - EXPECT_TRUE(ComponentMetadataImpl::uri_is_mavlinkftp( - "mftp://[;comp=39]/path/to/file.json", download_path, compid)); - EXPECT_EQ(compid, 39); - EXPECT_EQ(download_path, "/path/to/file.json"); -} - -TEST(ComponentMetadata, filename_from_uri) -{ - EXPECT_EQ( - ComponentMetadataImpl::filename_from_uri("http://url.com/file.json.xz"), "file.json.xz"); - EXPECT_EQ( - ComponentMetadataImpl::filename_from_uri("http://url.com/path/file.json?a=x&b=y"), - "file.json"); -} From 7f13ac466c87023aaf6568b278b04f1afd49f620 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 6 Jun 2024 13:35:25 +0200 Subject: [PATCH 5/9] plugins: add events implementation --- src/mavsdk/CMakeLists.txt | 3 + src/mavsdk/plugins/events/CMakeLists.txt | 16 + src/mavsdk/plugins/events/event_handler.cpp | 152 + src/mavsdk/plugins/events/event_handler.h | 66 + src/mavsdk/plugins/events/events.cpp | 222 + src/mavsdk/plugins/events/events_impl.cpp | 395 ++ src/mavsdk/plugins/events/events_impl.h | 69 + .../events/include/plugins/events/events.h | 315 ++ .../src/generated/events/events.grpc.pb.cc | 160 + .../src/generated/events/events.grpc.pb.h | 575 +++ .../src/generated/events/events.pb.cc | 3017 ++++++++++++ .../src/generated/events/events.pb.h | 4026 +++++++++++++++++ src/mavsdk_server/src/grpc_server.cpp | 8 + src/mavsdk_server/src/grpc_server.h | 17 + .../src/plugins/events/events_service_impl.h | 490 ++ src/plugins.txt | 1 + third_party/CMakeLists.txt | 10 +- third_party/libevents/CMakeLists.txt | 38 + 18 files changed, 9575 insertions(+), 5 deletions(-) create mode 100644 src/mavsdk/plugins/events/CMakeLists.txt create mode 100644 src/mavsdk/plugins/events/event_handler.cpp create mode 100644 src/mavsdk/plugins/events/event_handler.h create mode 100644 src/mavsdk/plugins/events/events.cpp create mode 100644 src/mavsdk/plugins/events/events_impl.cpp create mode 100644 src/mavsdk/plugins/events/events_impl.h create mode 100644 src/mavsdk/plugins/events/include/plugins/events/events.h create mode 100644 src/mavsdk_server/src/generated/events/events.grpc.pb.cc create mode 100644 src/mavsdk_server/src/generated/events/events.grpc.pb.h create mode 100644 src/mavsdk_server/src/generated/events/events.pb.cc create mode 100644 src/mavsdk_server/src/generated/events/events.pb.h create mode 100644 src/mavsdk_server/src/plugins/events/events_service_impl.h create mode 100644 third_party/libevents/CMakeLists.txt diff --git a/src/mavsdk/CMakeLists.txt b/src/mavsdk/CMakeLists.txt index 9b8d9a881..2336bfa8a 100644 --- a/src/mavsdk/CMakeLists.txt +++ b/src/mavsdk/CMakeLists.txt @@ -11,10 +11,13 @@ find_package(jsoncpp REQUIRED) hunter_add_package(tinyxml2) find_package(tinyxml2 REQUIRED) +find_package(libevents REQUIRED) + target_link_libraries(mavsdk PRIVATE JsonCpp::JsonCpp tinyxml2::tinyxml2 + LibEvents::LibEvents ) if (NOT APPLE AND NOT ANDROID AND NOT MSVC) diff --git a/src/mavsdk/plugins/events/CMakeLists.txt b/src/mavsdk/plugins/events/CMakeLists.txt new file mode 100644 index 000000000..60cc1eccf --- /dev/null +++ b/src/mavsdk/plugins/events/CMakeLists.txt @@ -0,0 +1,16 @@ +target_sources(mavsdk + PRIVATE + event_handler.cpp + events.cpp + events_impl.cpp +) + +target_include_directories(mavsdk PUBLIC + $ + $ + ) + +install(FILES + include/plugins/events/events.h + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/mavsdk/plugins/events +) \ No newline at end of file diff --git a/src/mavsdk/plugins/events/event_handler.cpp b/src/mavsdk/plugins/events/event_handler.cpp new file mode 100644 index 000000000..361579918 --- /dev/null +++ b/src/mavsdk/plugins/events/event_handler.cpp @@ -0,0 +1,152 @@ + +#include "event_handler.h" + +#include + +namespace mavsdk { + +EventHandler::EventHandler( + const std::string& profile, + handle_event_f handle_event_cb, + health_and_arming_checks_updated_f health_and_arming_checks_updated_cb, + SystemImpl& system_impl, + uint8_t system_id, + uint8_t component_id) : + _handle_event_cb(std::move(handle_event_cb)), + _health_and_arming_checks_updated_cb(std::move(health_and_arming_checks_updated_cb)), + _compid(component_id), + _system_impl(system_impl) +{ + auto error_cb = [component_id, this](int num_events_lost) { + _health_and_arming_checks.reset(); + LogWarn() << "Events got lost:" << num_events_lost << "comp_id:" << component_id; + }; + + const auto timeout_cb = [this](int timeout_ms) { + if (_timer_cookie != 0) { + _system_impl.unregister_timeout_handler(_timer_cookie); + _timer_cookie = 0; + } + if (timeout_ms > 0) { + _timer_cookie = _system_impl.register_timeout_handler( + [this]() { + const std::lock_guard lg{_protocol_mutex}; + _protocol->timerEvent(); + }, + timeout_ms / 1000.0); + } + }; + + const auto send_request_cb = [this](const mavlink_request_event_t& msg) { + mavlink_message_t message; + mavlink_msg_request_event_encode( + _system_impl.get_own_system_id(), _system_impl.get_own_component_id(), &message, &msg); + _system_impl.send_message(message); + }; + + _parser.setProfile(profile); + + _parser.formatters().url = [](const std::string& /*content*/, const std::string& link) { + return link; + }; + + events::ReceiveProtocol::Callbacks callbacks{ + error_cb, + send_request_cb, + std::bind(&EventHandler::got_event, this, std::placeholders::_1), + timeout_cb}; + _protocol = std::make_unique( + callbacks, + _system_impl.get_own_system_id(), + _system_impl.get_own_component_id(), + system_id, + component_id); + + _system_impl.register_mavlink_message_handler_with_compid( + MAVLINK_MSG_ID_EVENT, + _compid, + std::bind(&EventHandler::handle_mavlink_message, this, std::placeholders::_1), + &_message_handler_cookies[0]); + _system_impl.register_mavlink_message_handler_with_compid( + MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE, + _compid, + std::bind(&EventHandler::handle_mavlink_message, this, std::placeholders::_1), + &_message_handler_cookies[1]); + _system_impl.register_mavlink_message_handler_with_compid( + MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR, + _compid, + std::bind(&EventHandler::handle_mavlink_message, this, std::placeholders::_1), + &_message_handler_cookies[2]); +} +EventHandler::~EventHandler() +{ + if (_timer_cookie != 0) { + _system_impl.unregister_timeout_handler(_timer_cookie); + } + for (const auto& cookie : _message_handler_cookies) { + _system_impl.unregister_all_mavlink_message_handlers(cookie); + } +} +void EventHandler::set_metadata(const std::string& metadata_json) +{ + if (_parser.loadDefinitions(metadata_json)) { + if (_parser.hasDefinitions()) { + // do we have queued events? + for (const auto& event : _pending_events) { + got_event(event); + } + _pending_events.clear(); + } + } else { + LogErr() << "Failed to load events JSON metadata file"; + } +} + +std::optional EventHandler::get_mode_group(uint32_t custom_mode) const +{ + events::parser::Parser::NavigationModeGroups groups = _parser.navigationModeGroups(_compid); + for (auto group_iter : groups.groups) { + if (group_iter.second.find(custom_mode) != group_iter.second.end()) { + return group_iter.first; + } + } + return std::nullopt; +} +void EventHandler::handle_mavlink_message(const mavlink_message_t& message) +{ + const std::lock_guard lg{_protocol_mutex}; + _protocol->processMessage(message); +} +void EventHandler::got_event(const mavlink_event_t& event) +{ + if (!_parser.hasDefinitions()) { + if (_pending_events.size() > 50) { // Limit size (not expected to hit that limit) + _pending_events.clear(); + } + if (_pending_events.empty()) { // Print only for the first to avoid spamming + LogDebug() << "No metadata, queuing event, ID: " << event.id + << ", num pending: " << _pending_events.size(); + } + _pending_events.push_back(event); + return; + } + + std::unique_ptr parsed_event = + _parser.parse(events::EventType(event)); + if (parsed_event == nullptr) { + LogWarn() << "Got Event without known metadata: ID:" << event.id << "comp id:" << _compid; + return; + } + + // LogDebug() << "Got Event: ID: " << parsed_event->id() << " namespace: " << + // parsed_event->eventNamespace().c_str() << + // " name: " << parsed_event->name().c_str() << " msg: " << + // parsed_event->message().c_str(); + + if (_health_and_arming_checks.handleEvent(*parsed_event)) { + _health_and_arming_checks_valid = true; + _health_and_arming_checks_updated_cb(); + } + _handle_event_cb(std::move(parsed_event)); +} +} // namespace mavsdk diff --git a/src/mavsdk/plugins/events/event_handler.h b/src/mavsdk/plugins/events/event_handler.h new file mode 100644 index 000000000..230fd4af3 --- /dev/null +++ b/src/mavsdk/plugins/events/event_handler.h @@ -0,0 +1,66 @@ +#pragma once + +#include "system_impl.h" +#include +#include +#include + +#include "mavlink_include.h" +#include +#include +#include + +namespace mavsdk { + +/* + * Handles the events protocol for a single mavlink component + */ +class EventHandler { +public: + using handle_event_f = std::function)>; + using health_and_arming_checks_updated_f = std::function; + + EventHandler( + const std::string& profile, + handle_event_f handle_event_cb, + health_and_arming_checks_updated_f health_and_arming_checks_updated_cb, + SystemImpl& system_impl, + uint8_t system_id, + uint8_t component_id); + ~EventHandler(); + + void set_metadata(const std::string& metadata_json); + + const events::HealthAndArmingChecks::Results& health_and_arming_check_results() const + { + return _health_and_arming_checks.results(); + } + bool health_and_arming_check_results_valid() const { return _health_and_arming_checks_valid; } + + /** + * Get the mode group (used for the health and arming checks) from a custom_mode mavlink mode. + */ + std::optional get_mode_group(uint32_t custom_mode) const; + +private: + void got_event(const mavlink_event_t& event); + void handle_mavlink_message(const mavlink_message_t& message); + + std::mutex _protocol_mutex{}; + std::unique_ptr _protocol{nullptr}; + TimeoutHandler::Cookie _timer_cookie{0}; + events::parser::Parser _parser; + events::HealthAndArmingChecks _health_and_arming_checks; + bool _health_and_arming_checks_valid{false}; + const handle_event_f _handle_event_cb; + const health_and_arming_checks_updated_f _health_and_arming_checks_updated_cb; + const uint8_t _compid; + SystemImpl& _system_impl; + + std::vector + _pending_events; ///< stores incoming events until we have the metadata loaded + + std::array _message_handler_cookies{}; +}; + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/events/events.cpp b/src/mavsdk/plugins/events/events.cpp new file mode 100644 index 000000000..f70519dff --- /dev/null +++ b/src/mavsdk/plugins/events/events.cpp @@ -0,0 +1,222 @@ +// 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/events/events.proto) + +#include + +#include "events_impl.h" +#include "plugins/events/events.h" + +namespace mavsdk { + +using Event = Events::Event; +using HealthAndArmingCheckProblem = Events::HealthAndArmingCheckProblem; +using HealthAndArmingCheckMode = Events::HealthAndArmingCheckMode; +using HealthComponentReport = Events::HealthComponentReport; +using HealthAndArmingCheckReport = Events::HealthAndArmingCheckReport; + +Events::Events(System& system) : PluginBase(), _impl{std::make_unique(system)} {} + +Events::Events(std::shared_ptr system) : + PluginBase(), + _impl{std::make_unique(system)} +{} + +Events::~Events() {} + +Events::EventsHandle Events::subscribe_events(const EventsCallback& callback) +{ + return _impl->subscribe_events(callback); +} + +void Events::unsubscribe_events(EventsHandle handle) +{ + _impl->unsubscribe_events(handle); +} + +Events::HealthAndArmingChecksHandle +Events::subscribe_health_and_arming_checks(const HealthAndArmingChecksCallback& callback) +{ + return _impl->subscribe_health_and_arming_checks(callback); +} + +void Events::unsubscribe_health_and_arming_checks(HealthAndArmingChecksHandle handle) +{ + _impl->unsubscribe_health_and_arming_checks(handle); +} + +std::pair +Events::get_health_and_arming_checks_report() const +{ + return _impl->get_health_and_arming_checks_report(); +} + +bool operator==(const Events::Event& lhs, const Events::Event& rhs) +{ + return (rhs.compid == lhs.compid) && (rhs.message == lhs.message) && + (rhs.description == lhs.description) && (rhs.log_level == lhs.log_level) && + (rhs.event_namespace == lhs.event_namespace) && (rhs.event_name == lhs.event_name); +} + +std::ostream& operator<<(std::ostream& str, Events::Event const& event) +{ + str << std::setprecision(15); + str << "event:" << '\n' << "{\n"; + str << " compid: " << event.compid << '\n'; + str << " message: " << event.message << '\n'; + str << " description: " << event.description << '\n'; + str << " log_level: " << event.log_level << '\n'; + str << " event_namespace: " << event.event_namespace << '\n'; + str << " event_name: " << event.event_name << '\n'; + str << '}'; + return str; +} + +bool operator==( + const Events::HealthAndArmingCheckProblem& lhs, const Events::HealthAndArmingCheckProblem& rhs) +{ + return (rhs.message == lhs.message) && (rhs.description == lhs.description) && + (rhs.log_level == lhs.log_level) && (rhs.health_component == lhs.health_component); +} + +std::ostream& operator<<( + std::ostream& str, Events::HealthAndArmingCheckProblem const& health_and_arming_check_problem) +{ + str << std::setprecision(15); + str << "health_and_arming_check_problem:" << '\n' << "{\n"; + str << " message: " << health_and_arming_check_problem.message << '\n'; + str << " description: " << health_and_arming_check_problem.description << '\n'; + str << " log_level: " << health_and_arming_check_problem.log_level << '\n'; + str << " health_component: " << health_and_arming_check_problem.health_component << '\n'; + str << '}'; + return str; +} + +bool operator==( + const Events::HealthAndArmingCheckMode& lhs, const Events::HealthAndArmingCheckMode& rhs) +{ + return (rhs.mode_name == lhs.mode_name) && (rhs.can_arm_or_run == lhs.can_arm_or_run) && + (rhs.problems == lhs.problems); +} + +std::ostream& +operator<<(std::ostream& str, Events::HealthAndArmingCheckMode const& health_and_arming_check_mode) +{ + str << std::setprecision(15); + str << "health_and_arming_check_mode:" << '\n' << "{\n"; + str << " mode_name: " << health_and_arming_check_mode.mode_name << '\n'; + str << " can_arm_or_run: " << health_and_arming_check_mode.can_arm_or_run << '\n'; + str << " problems: ["; + for (auto it = health_and_arming_check_mode.problems.begin(); + it != health_and_arming_check_mode.problems.end(); + ++it) { + str << *it; + str << (it + 1 != health_and_arming_check_mode.problems.end() ? ", " : "]\n"); + } + str << '}'; + return str; +} + +bool operator==(const Events::HealthComponentReport& lhs, const Events::HealthComponentReport& rhs) +{ + return (rhs.name == lhs.name) && (rhs.label == lhs.label) && + (rhs.is_present == lhs.is_present) && (rhs.has_error == lhs.has_error) && + (rhs.has_warning == lhs.has_warning); +} + +std::ostream& +operator<<(std::ostream& str, Events::HealthComponentReport const& health_component_report) +{ + str << std::setprecision(15); + str << "health_component_report:" << '\n' << "{\n"; + str << " name: " << health_component_report.name << '\n'; + str << " label: " << health_component_report.label << '\n'; + str << " is_present: " << health_component_report.is_present << '\n'; + str << " has_error: " << health_component_report.has_error << '\n'; + str << " has_warning: " << health_component_report.has_warning << '\n'; + str << '}'; + return str; +} + +bool operator==( + const Events::HealthAndArmingCheckReport& lhs, const Events::HealthAndArmingCheckReport& rhs) +{ + return (rhs.current_mode_intention == lhs.current_mode_intention) && + (rhs.health_components == lhs.health_components) && + (rhs.all_problems == lhs.all_problems); +} + +std::ostream& operator<<( + std::ostream& str, Events::HealthAndArmingCheckReport const& health_and_arming_check_report) +{ + str << std::setprecision(15); + str << "health_and_arming_check_report:" << '\n' << "{\n"; + str << " current_mode_intention: " << health_and_arming_check_report.current_mode_intention + << '\n'; + str << " health_components: ["; + for (auto it = health_and_arming_check_report.health_components.begin(); + it != health_and_arming_check_report.health_components.end(); + ++it) { + str << *it; + str << (it + 1 != health_and_arming_check_report.health_components.end() ? ", " : "]\n"); + } + str << " all_problems: ["; + for (auto it = health_and_arming_check_report.all_problems.begin(); + it != health_and_arming_check_report.all_problems.end(); + ++it) { + str << *it; + str << (it + 1 != health_and_arming_check_report.all_problems.end() ? ", " : "]\n"); + } + str << '}'; + return str; +} + +std::ostream& operator<<(std::ostream& str, Events::Result const& result) +{ + switch (result) { + case Events::Result::Success: + return str << "Success"; + case Events::Result::NotAvailable: + return str << "Not Available"; + case Events::Result::ConnectionError: + return str << "Connection Error"; + case Events::Result::Unsupported: + return str << "Unsupported"; + case Events::Result::Denied: + return str << "Denied"; + case Events::Result::Failed: + return str << "Failed"; + case Events::Result::Timeout: + return str << "Timeout"; + case Events::Result::NoSystem: + return str << "No System"; + default: + return str << "Unknown"; + } +} + +std::ostream& operator<<(std::ostream& str, Events::LogLevel const& log_level) +{ + switch (log_level) { + case Events::LogLevel::Emergency: + return str << "Emergency"; + case Events::LogLevel::Alert: + return str << "Alert"; + case Events::LogLevel::Critical: + return str << "Critical"; + case Events::LogLevel::Error: + return str << "Error"; + case Events::LogLevel::Warning: + return str << "Warning"; + case Events::LogLevel::Notice: + return str << "Notice"; + case Events::LogLevel::Info: + return str << "Info"; + case Events::LogLevel::Debug: + return str << "Debug"; + default: + return str << "Unknown"; + } +} + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/events/events_impl.cpp b/src/mavsdk/plugins/events/events_impl.cpp new file mode 100644 index 000000000..1a16eb91e --- /dev/null +++ b/src/mavsdk/plugins/events/events_impl.cpp @@ -0,0 +1,395 @@ + +#include "events_impl.h" +#include "callback_list.tpp" +#include "unused.h" + +namespace mavsdk { + +EventsImpl::EventsImpl(System& system) : PluginImplBase(system) +{ + _system_impl->register_plugin(this); +} + +EventsImpl::EventsImpl(std::shared_ptr system) : PluginImplBase(std::move(system)) +{ + _system_impl->register_plugin(this); +} + +EventsImpl::~EventsImpl() +{ + _system_impl->unregister_plugin(this); +} + +void EventsImpl::init() +{ + _system_impl->register_mavlink_message_handler_with_compid( + MAVLINK_MSG_ID_HEARTBEAT, + MAV_COMP_ID_AUTOPILOT1, + std::bind(&EventsImpl::handle_heartbeat, this, std::placeholders::_1), + &_heartbeat_mode_cookie); +#ifdef MAVLINK_MSG_ID_CURRENT_MODE // Defined in development.xml MAVLink dialect + _system_impl->register_mavlink_message_handler_with_compid( + MAVLINK_MSG_ID_CURRENT_MODE, + MAV_COMP_ID_AUTOPILOT1, + std::bind(&EventsImpl::handle_current_mode, this, std::placeholders::_1), + &_current_mode_cookie); +#endif + + const std::lock_guard lg{_mutex}; + // Instantiate the autopilot component. It's not strictly required, it just makes sure to buffer + // events until we get the metadata + get_or_create_event_handler(MAV_COMP_ID_AUTOPILOT1); + + // Request metadata + _system_impl->component_metadata().subscribe_metadata_available( + [this](MavlinkComponentMetadata::MetadataUpdate update) { + if (update.type == MavlinkComponentMetadata::MetadataType::Events) { + set_metadata(update.compid, update.json_metadata); + } + }); + _system_impl->component_metadata().request_autopilot_component(); +} + +void EventsImpl::deinit() +{ + if (_current_mode_cookie) { + _system_impl->unregister_all_mavlink_message_handlers(_current_mode_cookie); + _current_mode_cookie = nullptr; + } + if (_heartbeat_mode_cookie) { + _system_impl->unregister_all_mavlink_message_handlers(_heartbeat_mode_cookie); + _heartbeat_mode_cookie = nullptr; + } +} + +void EventsImpl::enable() {} + +void EventsImpl::disable() {} + +EventHandler& EventsImpl::get_or_create_event_handler(uint8_t compid) +{ + auto event_data = _events.find(compid); + if (event_data == _events.end()) { + // Add new component + const std::string profile = "dev"; // Could also be "normal" + + auto event_handler = std::make_shared( + profile, + std::bind(&EventsImpl::handle_event, this, compid, std::placeholders::_1), + std::bind(&EventsImpl::handle_health_and_arming_check_update, this), + *_system_impl, + _system_impl->get_system_id(), + compid); + event_data = _events.insert(std::make_pair(compid, event_handler)).first; + } + return *event_data->second; +} + +void EventsImpl::set_metadata(uint8_t compid, const std::string& metadata_json) +{ + const std::lock_guard lg{_mutex}; + auto& event_handler = get_or_create_event_handler(compid); + event_handler.set_metadata(metadata_json); + + if (!event_handler.health_and_arming_check_results_valid() && + compid == MAV_COMP_ID_AUTOPILOT1) { + // Request arming checks to be reported + MavlinkCommandSender::CommandLong command{}; + command.command = MAV_CMD_RUN_PREARM_CHECKS; + command.target_component_id = _system_impl->get_autopilot_id(); + + _system_impl->send_command_async( + command, [this](MavlinkCommandSender::Result result, float) { + if (result != MavlinkCommandSender::Result::Success) { + LogWarn() << "command MAV_CMD_RUN_PREARM_CHECKS failed"; + } + }); + } +} + +void EventsImpl::handle_event(uint8_t compid, std::unique_ptr event) +{ + std::optional maybe_log_level = + external_log_level(event->eventData().log_levels); + + // Handle special groups & protocols + if (event->group() == "health" || event->group() == "arming_check") { + // These are displayed separately + return; + } + + // Show message according to the log level, don't show unknown event groups (might be part of a + // new protocol) + if (event->group() == "default" && maybe_log_level) { + std::string message = event->message(); + std::string description = event->description(); + + if (event->type() == "append_health_and_arming_messages" && event->numArguments() > 0) { + const uint32_t custom_mode = event->argumentValue(0).value.val_uint32_t; + const std::shared_ptr& event_handler = _events[compid]; + const auto maybe_mode_group = event_handler->get_mode_group(custom_mode); + if (maybe_mode_group) { + const int mode_group = maybe_mode_group.value(); + std::vector checks = + event_handler->health_and_arming_check_results().checks(mode_group); + std::vector message_checks; + for (const auto& check : checks) { + if (external_log_level(check.log_levels).value_or(Events::LogLevel::Debug) <= + Events::LogLevel::Warning) { + message_checks.push_back(check.message); + } + } + if (message_checks.empty()) { + // Add all + for (const auto& check : checks) { + message_checks.push_back(check.message); + } + } + if (!message.empty() && !message_checks.empty()) { + message += "\n"; + } + if (message_checks.size() == 1) { + message += message_checks[0]; + } else { + for (const auto& message_check : message_checks) { + message += "- " + message_check + "\n"; + } + } + } + } + + if (!message.empty()) { + on_new_displayable_event( + compid, std::move(event), maybe_log_level.value(), message, description); + } + } +} + +void EventsImpl::on_new_displayable_event( + uint8_t compid, + std::unique_ptr event, + Events::LogLevel log_level, + const std::string& message, + const std::string& description) +{ + // Notify subscribers + const std::lock_guard lg{_mutex}; + _events_callbacks.queue( + Events::Event{ + compid, message, description, log_level, event->eventNamespace(), event->name()}, + [this](const auto& func) { _system_impl->call_user_callback(func); }); +} + +void EventsImpl::handle_health_and_arming_check_update() +{ + // Notify subscribers + const std::lock_guard lg{_mutex}; + const auto report = get_health_and_arming_checks_report(); + if (report.first == Events::Result::Success) { + _health_and_arming_checks_callbacks.queue( + report.second, [this](const auto& func) { _system_impl->call_user_callback(func); }); + } +} +std::optional EventsImpl::external_log_level(uint8_t log_levels) +{ + const int external_log_level = log_levels & 0xF; + switch (external_log_level) { + case 0: + return Events::LogLevel::Emergency; + case 1: + return Events::LogLevel::Alert; + case 2: + return Events::LogLevel::Critical; + case 3: + return Events::LogLevel::Error; + case 4: + return Events::LogLevel::Warning; + case 5: + return Events::LogLevel::Notice; + case 6: + return Events::LogLevel::Info; + case 7: + return Events::LogLevel::Debug; + // 8: Protocol + // 9: Disabled + default: + break; + } + return std::nullopt; +} +Events::EventsHandle EventsImpl::subscribe_events(const Events::EventsCallback& callback) +{ + const std::lock_guard lg{_mutex}; + return _events_callbacks.subscribe(callback); +} +void EventsImpl::unsubscribe_events(Events::EventsHandle handle) +{ + const std::lock_guard lg{_mutex}; + _events_callbacks.unsubscribe(handle); +} +Events::HealthAndArmingChecksHandle EventsImpl::subscribe_health_and_arming_checks( + const Events::HealthAndArmingChecksCallback& callback) +{ + const std::lock_guard lg{_mutex}; + // Run callback immediately if the report is available + const auto report = get_health_and_arming_checks_report(); + if (report.first == Events::Result::Success) { + _system_impl->call_user_callback([temp_callback = callback, temp_report = report.second] { + temp_callback(temp_report); + }); + } + return _health_and_arming_checks_callbacks.subscribe(callback); +} +void EventsImpl::unsubscribe_health_and_arming_checks(Events::HealthAndArmingChecksHandle handle) +{ + const std::lock_guard lg{_mutex}; + _health_and_arming_checks_callbacks.unsubscribe(handle); +} +std::pair +EventsImpl::get_health_and_arming_checks_report() +{ + const auto& event_handler = get_or_create_event_handler(MAV_COMP_ID_AUTOPILOT1); + if (!event_handler.health_and_arming_check_results_valid()) { + return std::make_pair(Events::Result::NotAvailable, Events::HealthAndArmingCheckReport{}); + } + const uint32_t custom_mode = _maybe_custom_mode_user_intention.value_or(_custom_mode); + const auto maybe_current_mode_group = event_handler.get_mode_group(custom_mode); + if (!maybe_current_mode_group) { + LogDebug() << "Current mode not available (yet)"; + return std::make_pair(Events::Result::NotAvailable, Events::HealthAndArmingCheckReport{}); + } + + const auto& event_handler_results = event_handler.health_and_arming_check_results(); + Events::HealthAndArmingCheckReport report{}; + + auto get_problems = + [&event_handler_results](const std::vector& checks) { + std::vector problems; + for (const auto& check : checks) { + const auto maybe_log_level = external_log_level(check.log_levels); + if (maybe_log_level) { + problems.push_back(Events::HealthAndArmingCheckProblem{ + check.message, + check.description, + maybe_log_level.value(), + get_health_component_from_index( + event_handler_results, check.affected_health_component_index)}); + } + } + return problems; + }; + + // All problems + report.all_problems = get_problems(event_handler_results.checks()); + + // Current mode + const int current_mode_group = maybe_current_mode_group.value(); + report.current_mode_intention.problems = + get_problems(event_handler_results.checks(current_mode_group)); + report.current_mode_intention.can_arm_or_run = + _system_impl->is_armed() ? event_handler_results.canRun(current_mode_group) : + event_handler_results.canArm(current_mode_group); + report.current_mode_intention.mode_name = mode_name_from_custom_mode(custom_mode); + // We could add the results for other modes, like Takeoff or Mission, with allows to check if + // arming is possible for that mode independent of the current mode. + // For that, we need to get the custom_mode for these. + + // Health components + for (const auto& [component_name, component] : + event_handler_results.healthComponents().health_components) { + const Events::HealthComponentReport health_component_report{ + component_name, + component.label, + component.health.is_present, + component.health.error || component.arming_check.error, + component.health.warning || component.arming_check.warning}; + report.health_components.push_back(health_component_report); + } + + return std::make_pair(Events::Result::Success, report); +} +std::string EventsImpl::get_health_component_from_index( + const events::HealthAndArmingChecks::Results& results, int health_component_index) +{ + if (health_component_index != 0) { // 0 == none + for (const auto& [component_name, component] : + results.healthComponents().health_components) { + if (component.bitmask == (1ull << health_component_index)) { + return component_name; + } + } + } + return ""; +} +void EventsImpl::handle_current_mode(const mavlink_message_t& message) +{ + UNUSED(message); +#ifdef MAVLINK_MSG_ID_CURRENT_MODE + mavlink_current_mode_t current_mode; + mavlink_msg_current_mode_decode(&message, ¤t_mode); + if (current_mode.intended_custom_mode != 0) { // 0 == unknown/not supplied + const bool changed = + _maybe_custom_mode_user_intention.value_or(0) != current_mode.intended_custom_mode; + _maybe_custom_mode_user_intention = current_mode.intended_custom_mode; + if (changed) { + handle_health_and_arming_check_update(); + } + } +#endif +} +void EventsImpl::handle_heartbeat(const mavlink_message_t& message) +{ + mavlink_heartbeat_t heartbeat; + mavlink_msg_heartbeat_decode(&message, &heartbeat); + if (_custom_mode != heartbeat.custom_mode) { + _custom_mode = heartbeat.custom_mode; + if (!_maybe_custom_mode_user_intention) { + handle_health_and_arming_check_update(); + } + } +} +std::string EventsImpl::mode_name_from_custom_mode(uint32_t custom_mode) const +{ + // TODO: use Standard Modes MAVLink interface + switch (to_flight_mode_from_custom_mode( + _system_impl->autopilot(), _system_impl->get_vehicle_type(), custom_mode)) { + case FlightMode::FBWA: + return "FBWA"; + case FlightMode::Autotune: + return "Autotune"; + case FlightMode::Guided: + return "Guided"; + case FlightMode::Ready: + return "Ready"; + case FlightMode::Takeoff: + return "Takeoff"; + case FlightMode::Hold: + return "Hold"; + case FlightMode::Mission: + return "Mission"; + case FlightMode::ReturnToLaunch: + return "RTL"; + case FlightMode::Land: + return "Land"; + case FlightMode::Offboard: + return "Offboard"; + case FlightMode::FollowMe: + return "Follow Me"; + case FlightMode::Manual: + return "Manual"; + case FlightMode::Altctl: + return "Altitude"; + case FlightMode::Posctl: + return "Position"; + case FlightMode::Acro: + return "Acro"; + case FlightMode::Rattitude: + return "Rattitude"; + case FlightMode::Stabilized: + return "Stabilized"; + case FlightMode::Unknown: + break; + } + return "Unknown"; +} +} // namespace mavsdk diff --git a/src/mavsdk/plugins/events/events_impl.h b/src/mavsdk/plugins/events/events_impl.h new file mode 100644 index 000000000..94303f89b --- /dev/null +++ b/src/mavsdk/plugins/events/events_impl.h @@ -0,0 +1,69 @@ +#pragma once + +#include "plugins/events/events.h" +#include "plugin_impl_base.h" +#include "callback_list.h" + +#include "event_handler.h" + +namespace mavsdk { + +class EventsImpl : public PluginImplBase { +public: + explicit EventsImpl(System& system); + explicit EventsImpl(std::shared_ptr system); + ~EventsImpl() override; + + void init() override; + void deinit() override; + + void enable() override; + void disable() override; + + Events::EventsHandle subscribe_events(const Events::EventsCallback& callback); + void unsubscribe_events(Events::EventsHandle handle); + + Events::HealthAndArmingChecksHandle + subscribe_health_and_arming_checks(const Events::HealthAndArmingChecksCallback& callback); + void unsubscribe_health_and_arming_checks(Events::HealthAndArmingChecksHandle handle); + + std::pair + get_health_and_arming_checks_report(); + + void set_metadata(uint8_t compid, const std::string& metadata_json); + +private: + void handle_event(uint8_t compid, std::unique_ptr event); + void on_new_displayable_event( + uint8_t compid, + std::unique_ptr event, + Events::LogLevel log_level, + const std::string& message, + const std::string& description); + void handle_health_and_arming_check_update(); + EventHandler& get_or_create_event_handler(uint8_t compid); + void handle_current_mode(const mavlink_message_t& message); + void handle_heartbeat(const mavlink_message_t& message); + + std::string mode_name_from_custom_mode(uint32_t custom_mode) const; + + static std::string get_health_component_from_index( + const events::HealthAndArmingChecks::Results& results, int health_component_index); + + static std::optional external_log_level(uint8_t log_levels); + + std::unordered_map> + _events; ///< One protocol handler for each component ID + + std::recursive_mutex _mutex{}; + CallbackList _events_callbacks; + CallbackList _health_and_arming_checks_callbacks; + + std::optional + _maybe_custom_mode_user_intention; ///< current user intention if available + uint32_t _custom_mode{}; ///< current custom mode + void* _current_mode_cookie{}; + void* _heartbeat_mode_cookie{}; +}; + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/events/include/plugins/events/events.h b/src/mavsdk/plugins/events/include/plugins/events/events.h new file mode 100644 index 000000000..04d900191 --- /dev/null +++ b/src/mavsdk/plugins/events/include/plugins/events/events.h @@ -0,0 +1,315 @@ +// 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/events/events.proto) + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "plugin_base.h" + +#include "handle.h" + +namespace mavsdk { + +class System; +class EventsImpl; + +/** + * @brief Get event notifications, such as takeoff, or arming checks + */ +class Events : public PluginBase { +public: + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto events = Events(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit Events(System& system); // deprecated + + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto events = Events(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit Events(std::shared_ptr system); // new + + /** + * @brief Destructor (internal use only). + */ + ~Events() override; + + /** + * @brief + */ + enum class LogLevel { + Emergency, /**< @brief. */ + Alert, /**< @brief. */ + Critical, /**< @brief. */ + Error, /**< @brief. */ + Warning, /**< @brief. */ + Notice, /**< @brief. */ + Info, /**< @brief. */ + Debug, /**< @brief. */ + }; + + /** + * @brief Stream operator to print information about a `Events::LogLevel`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Events::LogLevel const& log_level); + + /** + * @brief + */ + struct Event { + uint32_t compid{}; /**< @brief The source component ID of the event */ + std::string message{}; /**< @brief Short, single-line message */ + std::string + description{}; /**< @brief Detailed description (optional, might be multiple lines) */ + LogLevel log_level{}; /**< @brief */ + std::string event_namespace{}; /**< @brief Namespace, e.g. "px4" */ + std::string event_name{}; /**< @brief Event name (unique within the namespace) */ + }; + + /** + * @brief Equal operator to compare two `Events::Event` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const Events::Event& lhs, const Events::Event& rhs); + + /** + * @brief Stream operator to print information about a `Events::Event`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Events::Event const& event); + + /** + * @brief + */ + struct HealthAndArmingCheckProblem { + std::string message{}; /**< @brief Short, single-line message */ + std::string + description{}; /**< @brief Detailed description (optional, might be multiple lines) */ + LogLevel log_level{}; /**< @brief */ + std::string health_component{}; /**< @brief Associated health component, e.g. "gps" */ + }; + + /** + * @brief Equal operator to compare two `Events::HealthAndArmingCheckProblem` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==( + const Events::HealthAndArmingCheckProblem& lhs, + const Events::HealthAndArmingCheckProblem& rhs); + + /** + * @brief Stream operator to print information about a `Events::HealthAndArmingCheckProblem`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<( + std::ostream& str, + Events::HealthAndArmingCheckProblem const& health_and_arming_check_problem); + + /** + * @brief Arming checks for a specific mode + */ + struct HealthAndArmingCheckMode { + std::string mode_name{}; /**< @brief Mode name, e.g. "Position" */ + bool can_arm_or_run{}; /**< @brief If disarmed: indicated if arming is possible. If armed: + indicates if the mode can be selected */ + std::vector + problems{}; /**< @brief List of reported problems for the mode */ + }; + + /** + * @brief Equal operator to compare two `Events::HealthAndArmingCheckMode` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==( + const Events::HealthAndArmingCheckMode& lhs, const Events::HealthAndArmingCheckMode& rhs); + + /** + * @brief Stream operator to print information about a `Events::HealthAndArmingCheckMode`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<( + std::ostream& str, Events::HealthAndArmingCheckMode const& health_and_arming_check_mode); + + /** + * @brief + */ + struct HealthComponentReport { + std::string name{}; /**< @brief Unique component name, e.g. "gps" */ + std::string label{}; /**< @brief Human readable label of the component, e.g. "GPS" or + "Accelerometer" */ + bool is_present{}; /**< @brief If the component is present */ + bool has_error{}; /**< @brief If the component has errors */ + bool has_warning{}; /**< @brief If the component has warnings */ + }; + + /** + * @brief Equal operator to compare two `Events::HealthComponentReport` objects. + * + * @return `true` if items are equal. + */ + friend bool + operator==(const Events::HealthComponentReport& lhs, const Events::HealthComponentReport& rhs); + + /** + * @brief Stream operator to print information about a `Events::HealthComponentReport`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, Events::HealthComponentReport const& health_component_report); + + /** + * @brief + */ + struct HealthAndArmingCheckReport { + HealthAndArmingCheckMode + current_mode_intention{}; /**< @brief Report for currently intended mode */ + std::vector + health_components{}; /**< @brief Health components list (e.g. for "gps") */ + std::vector + all_problems{}; /**< @brief Complete list of problems */ + }; + + /** + * @brief Equal operator to compare two `Events::HealthAndArmingCheckReport` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==( + const Events::HealthAndArmingCheckReport& lhs, + const Events::HealthAndArmingCheckReport& rhs); + + /** + * @brief Stream operator to print information about a `Events::HealthAndArmingCheckReport`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<( + std::ostream& str, + Events::HealthAndArmingCheckReport const& health_and_arming_check_report); + + /** + * @brief + */ + enum class Result { + Success, /**< @brief. */ + NotAvailable, /**< @brief. */ + ConnectionError, /**< @brief. */ + Unsupported, /**< @brief. */ + Denied, /**< @brief. */ + Failed, /**< @brief. */ + Timeout, /**< @brief. */ + NoSystem, /**< @brief. */ + }; + + /** + * @brief Stream operator to print information about a `Events::Result`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Events::Result const& result); + + /** + * @brief Callback type for asynchronous Events calls. + */ + using ResultCallback = std::function; + + /** + * @brief Callback type for subscribe_events. + */ + using EventsCallback = std::function; + + /** + * @brief Handle type for subscribe_events. + */ + using EventsHandle = Handle; + + /** + * @brief Subscribe to event updates. + */ + EventsHandle subscribe_events(const EventsCallback& callback); + + /** + * @brief Unsubscribe from subscribe_events + */ + void unsubscribe_events(EventsHandle handle); + + /** + * @brief Callback type for subscribe_health_and_arming_checks. + */ + using HealthAndArmingChecksCallback = std::function; + + /** + * @brief Handle type for subscribe_health_and_arming_checks. + */ + using HealthAndArmingChecksHandle = Handle; + + /** + * @brief Subscribe to arming check updates. + */ + HealthAndArmingChecksHandle + subscribe_health_and_arming_checks(const HealthAndArmingChecksCallback& callback); + + /** + * @brief Unsubscribe from subscribe_health_and_arming_checks + */ + void unsubscribe_health_and_arming_checks(HealthAndArmingChecksHandle handle); + + /** + * @brief Get the latest report. + * + * This function is blocking. + * + * @return Result of request. + */ + std::pair + get_health_and_arming_checks_report() const; + + /** + * @brief Copy constructor. + */ + Events(const Events& other); + + /** + * @brief Equality operator (object is not copyable). + */ + const Events& operator=(const Events&) = 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/generated/events/events.grpc.pb.cc b/src/mavsdk_server/src/generated/events/events.grpc.pb.cc new file mode 100644 index 000000000..fdda73da9 --- /dev/null +++ b/src/mavsdk_server/src/generated/events/events.grpc.pb.cc @@ -0,0 +1,160 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: events/events.proto + +#include "events/events.pb.h" +#include "events/events.grpc.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +namespace mavsdk { +namespace rpc { +namespace events { + +static const char* EventsService_method_names[] = { + "/mavsdk.rpc.events.EventsService/SubscribeEvents", + "/mavsdk.rpc.events.EventsService/SubscribeHealthAndArmingChecks", + "/mavsdk.rpc.events.EventsService/GetHealthAndArmingChecksReport", +}; + +std::unique_ptr< EventsService::Stub> EventsService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { + (void)options; + std::unique_ptr< EventsService::Stub> stub(new EventsService::Stub(channel, options)); + return stub; +} + +EventsService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) + : channel_(channel), rpcmethod_SubscribeEvents_(EventsService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeHealthAndArmingChecks_(EventsService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_GetHealthAndArmingChecksReport_(EventsService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + {} + +::grpc::ClientReader< ::mavsdk::rpc::events::EventsResponse>* EventsService::Stub::SubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::events::EventsResponse>::Create(channel_.get(), rpcmethod_SubscribeEvents_, context, request); +} + +void EventsService::Stub::async::SubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::events::EventsResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::events::EventsResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeEvents_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::events::EventsResponse>* EventsService::Stub::AsyncSubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::events::EventsResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeEvents_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::events::EventsResponse>* EventsService::Stub::PrepareAsyncSubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::events::EventsResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeEvents_, context, request, false, nullptr); +} + +::grpc::ClientReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* EventsService::Stub::SubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>::Create(channel_.get(), rpcmethod_SubscribeHealthAndArmingChecks_, context, request); +} + +void EventsService::Stub::async::SubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeHealthAndArmingChecks_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* EventsService::Stub::AsyncSubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeHealthAndArmingChecks_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* EventsService::Stub::PrepareAsyncSubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeHealthAndArmingChecks_, context, request, false, nullptr); +} + +::grpc::Status EventsService::Stub::GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetHealthAndArmingChecksReport_, context, request, response); +} + +void EventsService::Stub::async::GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetHealthAndArmingChecksReport_, context, request, response, std::move(f)); +} + +void EventsService::Stub::async::GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetHealthAndArmingChecksReport_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* EventsService::Stub::PrepareAsyncGetHealthAndArmingChecksReportRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetHealthAndArmingChecksReport_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* EventsService::Stub::AsyncGetHealthAndArmingChecksReportRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetHealthAndArmingChecksReportRaw(context, request, cq); + result->StartCall(); + return result; +} + +EventsService::Service::Service() { + AddMethod(new ::grpc::internal::RpcServiceMethod( + EventsService_method_names[0], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< EventsService::Service, ::mavsdk::rpc::events::SubscribeEventsRequest, ::mavsdk::rpc::events::EventsResponse>( + [](EventsService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::events::SubscribeEventsRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::events::EventsResponse>* writer) { + return service->SubscribeEvents(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + EventsService_method_names[1], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< EventsService::Service, ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest, ::mavsdk::rpc::events::HealthAndArmingChecksResponse>( + [](EventsService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::events::HealthAndArmingChecksResponse>* writer) { + return service->SubscribeHealthAndArmingChecks(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + EventsService_method_names[2], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< EventsService::Service, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](EventsService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* req, + ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* resp) { + return service->GetHealthAndArmingChecksReport(ctx, req, resp); + }, this))); +} + +EventsService::Service::~Service() { +} + +::grpc::Status EventsService::Service::SubscribeEvents(::grpc::ServerContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::events::EventsResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status EventsService::Service::SubscribeHealthAndArmingChecks(::grpc::ServerContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status EventsService::Service::GetHealthAndArmingChecksReport(::grpc::ServerContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + + +} // namespace mavsdk +} // namespace rpc +} // namespace events + diff --git a/src/mavsdk_server/src/generated/events/events.grpc.pb.h b/src/mavsdk_server/src/generated/events/events.grpc.pb.h new file mode 100644 index 000000000..827e3ab4e --- /dev/null +++ b/src/mavsdk_server/src/generated/events/events.grpc.pb.h @@ -0,0 +1,575 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: events/events.proto +#ifndef GRPC_events_2fevents_2eproto__INCLUDED +#define GRPC_events_2fevents_2eproto__INCLUDED + +#include "events/events.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 events { + +// Get event notifications, such as takeoff, or arming checks +class EventsService final { + public: + static constexpr char const* service_full_name() { + return "mavsdk.rpc.events.EventsService"; + } + class StubInterface { + public: + virtual ~StubInterface() {} + // + // Subscribe to event updates. + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::events::EventsResponse>> SubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::events::EventsResponse>>(SubscribeEventsRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::EventsResponse>> AsyncSubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::EventsResponse>>(AsyncSubscribeEventsRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::EventsResponse>> PrepareAsyncSubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::EventsResponse>>(PrepareAsyncSubscribeEventsRaw(context, request, cq)); + } + // + // Subscribe to arming check updates. + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>> SubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>>(SubscribeHealthAndArmingChecksRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>> AsyncSubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>>(AsyncSubscribeHealthAndArmingChecksRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>> PrepareAsyncSubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>>(PrepareAsyncSubscribeHealthAndArmingChecksRaw(context, request, cq)); + } + // + // Get the latest report. + virtual ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>> AsyncGetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>>(AsyncGetHealthAndArmingChecksReportRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>> PrepareAsyncGetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>>(PrepareAsyncGetHealthAndArmingChecksReportRaw(context, request, cq)); + } + class async_interface { + public: + virtual ~async_interface() {} + // + // Subscribe to event updates. + virtual void SubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::events::EventsResponse>* reactor) = 0; + // + // Subscribe to arming check updates. + virtual void SubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* reactor) = 0; + // + // Get the latest report. + virtual void GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response, std::function) = 0; + virtual void GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* 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::ClientReaderInterface< ::mavsdk::rpc::events::EventsResponse>* SubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::EventsResponse>* AsyncSubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::EventsResponse>* PrepareAsyncSubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* SubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* AsyncSubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* PrepareAsyncSubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* AsyncGetHealthAndArmingChecksReportRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* PrepareAsyncGetHealthAndArmingChecksReportRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& 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()); + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::events::EventsResponse>> SubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::events::EventsResponse>>(SubscribeEventsRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::EventsResponse>> AsyncSubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::EventsResponse>>(AsyncSubscribeEventsRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::EventsResponse>> PrepareAsyncSubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::EventsResponse>>(PrepareAsyncSubscribeEventsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>> SubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>>(SubscribeHealthAndArmingChecksRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>> AsyncSubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>>(AsyncSubscribeHealthAndArmingChecksRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>> PrepareAsyncSubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>>(PrepareAsyncSubscribeHealthAndArmingChecksRaw(context, request, cq)); + } + ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>> AsyncGetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>>(AsyncGetHealthAndArmingChecksReportRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>> PrepareAsyncGetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>>(PrepareAsyncGetHealthAndArmingChecksReportRaw(context, request, cq)); + } + class async final : + public StubInterface::async_interface { + public: + void SubscribeEvents(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::events::EventsResponse>* reactor) override; + void SubscribeHealthAndArmingChecks(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* reactor) override; + void GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response, std::function) override; + void GetHealthAndArmingChecksReport(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* 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::ClientReader< ::mavsdk::rpc::events::EventsResponse>* SubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::EventsResponse>* AsyncSubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::EventsResponse>* PrepareAsyncSubscribeEventsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* SubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* AsyncSubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* PrepareAsyncSubscribeHealthAndArmingChecksRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* AsyncGetHealthAndArmingChecksReportRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* PrepareAsyncGetHealthAndArmingChecksReportRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest& request, ::grpc::CompletionQueue* cq) override; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeEvents_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeHealthAndArmingChecks_; + const ::grpc::internal::RpcMethod rpcmethod_GetHealthAndArmingChecksReport_; + }; + 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(); + // + // Subscribe to event updates. + virtual ::grpc::Status SubscribeEvents(::grpc::ServerContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::events::EventsResponse>* writer); + // + // Subscribe to arming check updates. + virtual ::grpc::Status SubscribeHealthAndArmingChecks(::grpc::ServerContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* writer); + // + // Get the latest report. + virtual ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ServerContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response); + }; + template + class WithAsyncMethod_SubscribeEvents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeEvents() { + ::grpc::Service::MarkMethodAsync(0); + } + ~WithAsyncMethod_SubscribeEvents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeEvents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeEventsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::EventsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeEvents(::grpc::ServerContext* context, ::mavsdk::rpc::events::SubscribeEventsRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::events::EventsResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(0, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeHealthAndArmingChecks : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeHealthAndArmingChecks() { + ::grpc::Service::MarkMethodAsync(1); + } + ~WithAsyncMethod_SubscribeHealthAndArmingChecks() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeHealthAndArmingChecks(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeHealthAndArmingChecks(::grpc::ServerContext* context, ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(1, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_GetHealthAndArmingChecksReport : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_GetHealthAndArmingChecksReport() { + ::grpc::Service::MarkMethodAsync(2); + } + ~WithAsyncMethod_GetHealthAndArmingChecksReport() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* /*request*/, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetHealthAndArmingChecksReport(::grpc::ServerContext* context, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SubscribeEvents > > AsyncService; + template + class WithCallbackMethod_SubscribeEvents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeEvents() { + ::grpc::Service::MarkMethodCallback(0, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::events::SubscribeEventsRequest, ::mavsdk::rpc::events::EventsResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::events::SubscribeEventsRequest* request) { return this->SubscribeEvents(context, request); })); + } + ~WithCallbackMethod_SubscribeEvents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeEvents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeEventsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::EventsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::events::EventsResponse>* SubscribeEvents( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeEventsRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeHealthAndArmingChecks : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeHealthAndArmingChecks() { + ::grpc::Service::MarkMethodCallback(1, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest, ::mavsdk::rpc::events::HealthAndArmingChecksResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* request) { return this->SubscribeHealthAndArmingChecks(context, request); })); + } + ~WithCallbackMethod_SubscribeHealthAndArmingChecks() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeHealthAndArmingChecks(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* SubscribeHealthAndArmingChecks( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_GetHealthAndArmingChecksReport : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_GetHealthAndArmingChecksReport() { + ::grpc::Service::MarkMethodCallback(2, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* request, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* response) { return this->GetHealthAndArmingChecksReport(context, request, response); }));} + void SetMessageAllocatorFor_GetHealthAndArmingChecksReport( + ::grpc::MessageAllocator< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_GetHealthAndArmingChecksReport() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* /*request*/, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetHealthAndArmingChecksReport( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* /*request*/, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SubscribeEvents > > CallbackService; + typedef CallbackService ExperimentalCallbackService; + template + class WithGenericMethod_SubscribeEvents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeEvents() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_SubscribeEvents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeEvents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeEventsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::EventsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeHealthAndArmingChecks : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeHealthAndArmingChecks() { + ::grpc::Service::MarkMethodGeneric(1); + } + ~WithGenericMethod_SubscribeHealthAndArmingChecks() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeHealthAndArmingChecks(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_GetHealthAndArmingChecksReport : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_GetHealthAndArmingChecksReport() { + ::grpc::Service::MarkMethodGeneric(2); + } + ~WithGenericMethod_GetHealthAndArmingChecksReport() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* /*request*/, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithRawMethod_SubscribeEvents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeEvents() { + ::grpc::Service::MarkMethodRaw(0); + } + ~WithRawMethod_SubscribeEvents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeEvents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeEventsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::EventsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeEvents(::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(0, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeHealthAndArmingChecks : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeHealthAndArmingChecks() { + ::grpc::Service::MarkMethodRaw(1); + } + ~WithRawMethod_SubscribeHealthAndArmingChecks() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeHealthAndArmingChecks(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeHealthAndArmingChecks(::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(1, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_GetHealthAndArmingChecksReport : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetHealthAndArmingChecksReport() { + ::grpc::Service::MarkMethodRaw(2); + } + ~WithRawMethod_GetHealthAndArmingChecksReport() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* /*request*/, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetHealthAndArmingChecksReport(::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(2, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawCallbackMethod_SubscribeEvents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeEvents() { + ::grpc::Service::MarkMethodRawCallback(0, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeEvents(context, request); })); + } + ~WithRawCallbackMethod_SubscribeEvents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeEvents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeEventsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::EventsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeEvents( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeHealthAndArmingChecks : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeHealthAndArmingChecks() { + ::grpc::Service::MarkMethodRawCallback(1, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeHealthAndArmingChecks(context, request); })); + } + ~WithRawCallbackMethod_SubscribeHealthAndArmingChecks() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeHealthAndArmingChecks(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeHealthAndArmingChecks( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_GetHealthAndArmingChecksReport : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetHealthAndArmingChecksReport() { + ::grpc::Service::MarkMethodRawCallback(2, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetHealthAndArmingChecksReport(context, request, response); })); + } + ~WithRawCallbackMethod_GetHealthAndArmingChecksReport() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* /*request*/, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetHealthAndArmingChecksReport( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithStreamedUnaryMethod_GetHealthAndArmingChecksReport : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetHealthAndArmingChecksReport() { + ::grpc::Service::MarkMethodStreamed(2, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* streamer) { + return this->StreamedGetHealthAndArmingChecksReport(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetHealthAndArmingChecksReport() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetHealthAndArmingChecksReport(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest* /*request*/, ::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetHealthAndArmingChecksReport(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest,::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_GetHealthAndArmingChecksReport StreamedUnaryService; + template + class WithSplitStreamingMethod_SubscribeEvents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeEvents() { + ::grpc::Service::MarkMethodStreamed(0, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::events::SubscribeEventsRequest, ::mavsdk::rpc::events::EventsResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::events::SubscribeEventsRequest, ::mavsdk::rpc::events::EventsResponse>* streamer) { + return this->StreamedSubscribeEvents(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeEvents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeEvents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeEventsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::EventsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeEvents(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::events::SubscribeEventsRequest,::mavsdk::rpc::events::EventsResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeHealthAndArmingChecks : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeHealthAndArmingChecks() { + ::grpc::Service::MarkMethodStreamed(1, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest, ::mavsdk::rpc::events::HealthAndArmingChecksResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest, ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* streamer) { + return this->StreamedSubscribeHealthAndArmingChecks(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeHealthAndArmingChecks() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeHealthAndArmingChecks(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::events::HealthAndArmingChecksResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeHealthAndArmingChecks(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest,::mavsdk::rpc::events::HealthAndArmingChecksResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeEvents > SplitStreamedService; + typedef WithSplitStreamingMethod_SubscribeEvents > > StreamedService; +}; + +} // namespace events +} // namespace rpc +} // namespace mavsdk + + +#endif // GRPC_events_2fevents_2eproto__INCLUDED diff --git a/src/mavsdk_server/src/generated/events/events.pb.cc b/src/mavsdk_server/src/generated/events/events.pb.cc new file mode 100644 index 000000000..91546d2e5 --- /dev/null +++ b/src/mavsdk_server/src/generated/events/events.pb.cc @@ -0,0 +1,3017 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: events/events.proto + +#include "events/events.pb.h" + +#include +#include "google/protobuf/io/coded_stream.h" +#include "google/protobuf/extension_set.h" +#include "google/protobuf/wire_format_lite.h" +#include "google/protobuf/descriptor.h" +#include "google/protobuf/generated_message_reflection.h" +#include "google/protobuf/reflection_ops.h" +#include "google/protobuf/wire_format.h" +#include "google/protobuf/generated_message_tctable_impl.h" +// @@protoc_insertion_point(includes) + +// Must be included last. +#include "google/protobuf/port_def.inc" +PROTOBUF_PRAGMA_INIT_SEG +namespace _pb = ::google::protobuf; +namespace _pbi = ::google::protobuf::internal; +namespace _fl = ::google::protobuf::internal::field_layout; +namespace mavsdk { +namespace rpc { +namespace events { + template +PROTOBUF_CONSTEXPR SubscribeHealthAndArmingChecksRequest::SubscribeHealthAndArmingChecksRequest(::_pbi::ConstantInitialized) {} +struct SubscribeHealthAndArmingChecksRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeHealthAndArmingChecksRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeHealthAndArmingChecksRequestDefaultTypeInternal() {} + union { + SubscribeHealthAndArmingChecksRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeHealthAndArmingChecksRequestDefaultTypeInternal _SubscribeHealthAndArmingChecksRequest_default_instance_; + template +PROTOBUF_CONSTEXPR SubscribeEventsRequest::SubscribeEventsRequest(::_pbi::ConstantInitialized) {} +struct SubscribeEventsRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeEventsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeEventsRequestDefaultTypeInternal() {} + union { + SubscribeEventsRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeEventsRequestDefaultTypeInternal _SubscribeEventsRequest_default_instance_; + +inline constexpr HealthComponentReport::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : name_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + label_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + is_present_{false}, + has_error_{false}, + has_warning_{false}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR HealthComponentReport::HealthComponentReport(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct HealthComponentReportDefaultTypeInternal { + PROTOBUF_CONSTEXPR HealthComponentReportDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~HealthComponentReportDefaultTypeInternal() {} + union { + HealthComponentReport _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 HealthComponentReportDefaultTypeInternal _HealthComponentReport_default_instance_; + +inline constexpr HealthAndArmingCheckProblem::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : message_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + description_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + health_component_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + log_level_{static_cast< ::mavsdk::rpc::events::LogLevel >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR HealthAndArmingCheckProblem::HealthAndArmingCheckProblem(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct HealthAndArmingCheckProblemDefaultTypeInternal { + PROTOBUF_CONSTEXPR HealthAndArmingCheckProblemDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~HealthAndArmingCheckProblemDefaultTypeInternal() {} + union { + HealthAndArmingCheckProblem _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 HealthAndArmingCheckProblemDefaultTypeInternal _HealthAndArmingCheckProblem_default_instance_; + template +PROTOBUF_CONSTEXPR GetHealthAndArmingChecksReportRequest::GetHealthAndArmingChecksReportRequest(::_pbi::ConstantInitialized) {} +struct GetHealthAndArmingChecksReportRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetHealthAndArmingChecksReportRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetHealthAndArmingChecksReportRequestDefaultTypeInternal() {} + union { + GetHealthAndArmingChecksReportRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetHealthAndArmingChecksReportRequestDefaultTypeInternal _GetHealthAndArmingChecksReportRequest_default_instance_; + +inline constexpr EventsResult::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : result_str_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + result_{static_cast< ::mavsdk::rpc::events::EventsResult_Result >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR EventsResult::EventsResult(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct EventsResultDefaultTypeInternal { + PROTOBUF_CONSTEXPR EventsResultDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~EventsResultDefaultTypeInternal() {} + union { + EventsResult _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 EventsResultDefaultTypeInternal _EventsResult_default_instance_; + +inline constexpr Event::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : message_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + description_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + event_namespace_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + event_name_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + compid_{0u}, + log_level_{static_cast< ::mavsdk::rpc::events::LogLevel >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR Event::Event(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct EventDefaultTypeInternal { + PROTOBUF_CONSTEXPR EventDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~EventDefaultTypeInternal() {} + union { + Event _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 EventDefaultTypeInternal _Event_default_instance_; + +inline constexpr HealthAndArmingCheckMode::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : problems_{}, + mode_name_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + can_arm_or_run_{false}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR HealthAndArmingCheckMode::HealthAndArmingCheckMode(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct HealthAndArmingCheckModeDefaultTypeInternal { + PROTOBUF_CONSTEXPR HealthAndArmingCheckModeDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~HealthAndArmingCheckModeDefaultTypeInternal() {} + union { + HealthAndArmingCheckMode _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 HealthAndArmingCheckModeDefaultTypeInternal _HealthAndArmingCheckMode_default_instance_; + +inline constexpr EventsResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + event_{nullptr} {} + +template +PROTOBUF_CONSTEXPR EventsResponse::EventsResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct EventsResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR EventsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~EventsResponseDefaultTypeInternal() {} + union { + EventsResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 EventsResponseDefaultTypeInternal _EventsResponse_default_instance_; + +inline constexpr HealthAndArmingCheckReport::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + health_components_{}, + all_problems_{}, + current_mode_intention_{nullptr} {} + +template +PROTOBUF_CONSTEXPR HealthAndArmingCheckReport::HealthAndArmingCheckReport(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct HealthAndArmingCheckReportDefaultTypeInternal { + PROTOBUF_CONSTEXPR HealthAndArmingCheckReportDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~HealthAndArmingCheckReportDefaultTypeInternal() {} + union { + HealthAndArmingCheckReport _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 HealthAndArmingCheckReportDefaultTypeInternal _HealthAndArmingCheckReport_default_instance_; + +inline constexpr HealthAndArmingChecksResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + report_{nullptr} {} + +template +PROTOBUF_CONSTEXPR HealthAndArmingChecksResponse::HealthAndArmingChecksResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct HealthAndArmingChecksResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR HealthAndArmingChecksResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~HealthAndArmingChecksResponseDefaultTypeInternal() {} + union { + HealthAndArmingChecksResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 HealthAndArmingChecksResponseDefaultTypeInternal _HealthAndArmingChecksResponse_default_instance_; + +inline constexpr GetHealthAndArmingChecksReportResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + events_result_{nullptr}, + report_{nullptr} {} + +template +PROTOBUF_CONSTEXPR GetHealthAndArmingChecksReportResponse::GetHealthAndArmingChecksReportResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetHealthAndArmingChecksReportResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetHealthAndArmingChecksReportResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetHealthAndArmingChecksReportResponseDefaultTypeInternal() {} + union { + GetHealthAndArmingChecksReportResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetHealthAndArmingChecksReportResponseDefaultTypeInternal _GetHealthAndArmingChecksReportResponse_default_instance_; +} // namespace events +} // namespace rpc +} // namespace mavsdk +static ::_pb::Metadata file_level_metadata_events_2fevents_2eproto[12]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_events_2fevents_2eproto[2]; +static constexpr const ::_pb::ServiceDescriptor** + file_level_service_descriptors_events_2fevents_2eproto = nullptr; +const ::uint32_t TableStruct_events_2fevents_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( + protodesc_cold) = { + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::Event, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::Event, _impl_.compid_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::Event, _impl_.message_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::Event, _impl_.description_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::Event, _impl_.log_level_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::Event, _impl_.event_namespace_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::Event, _impl_.event_name_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckProblem, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckProblem, _impl_.message_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckProblem, _impl_.description_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckProblem, _impl_.log_level_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckProblem, _impl_.health_component_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckMode, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckMode, _impl_.mode_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckMode, _impl_.can_arm_or_run_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckMode, _impl_.problems_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthComponentReport, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthComponentReport, _impl_.name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthComponentReport, _impl_.label_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthComponentReport, _impl_.is_present_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthComponentReport, _impl_.has_error_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthComponentReport, _impl_.has_warning_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckReport, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckReport, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckReport, _impl_.current_mode_intention_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckReport, _impl_.health_components_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingCheckReport, _impl_.all_problems_), + 0, + ~0u, + ~0u, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::EventsResult, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::EventsResult, _impl_.result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::EventsResult, _impl_.result_str_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::SubscribeEventsRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::EventsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::EventsResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::EventsResponse, _impl_.event_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingChecksResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingChecksResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::HealthAndArmingChecksResponse, _impl_.report_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse, _impl_.events_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse, _impl_.report_), + 0, + 1, +}; + +static const ::_pbi::MigrationSchema + schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + {0, -1, -1, sizeof(::mavsdk::rpc::events::Event)}, + {14, -1, -1, sizeof(::mavsdk::rpc::events::HealthAndArmingCheckProblem)}, + {26, -1, -1, sizeof(::mavsdk::rpc::events::HealthAndArmingCheckMode)}, + {37, -1, -1, sizeof(::mavsdk::rpc::events::HealthComponentReport)}, + {50, 61, -1, sizeof(::mavsdk::rpc::events::HealthAndArmingCheckReport)}, + {64, -1, -1, sizeof(::mavsdk::rpc::events::EventsResult)}, + {74, -1, -1, sizeof(::mavsdk::rpc::events::SubscribeEventsRequest)}, + {82, 91, -1, sizeof(::mavsdk::rpc::events::EventsResponse)}, + {92, -1, -1, sizeof(::mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest)}, + {100, 109, -1, sizeof(::mavsdk::rpc::events::HealthAndArmingChecksResponse)}, + {110, -1, -1, sizeof(::mavsdk::rpc::events::GetHealthAndArmingChecksReportRequest)}, + {118, 128, -1, sizeof(::mavsdk::rpc::events::GetHealthAndArmingChecksReportResponse)}, +}; + +static const ::_pb::Message* const file_default_instances[] = { + &::mavsdk::rpc::events::_Event_default_instance_._instance, + &::mavsdk::rpc::events::_HealthAndArmingCheckProblem_default_instance_._instance, + &::mavsdk::rpc::events::_HealthAndArmingCheckMode_default_instance_._instance, + &::mavsdk::rpc::events::_HealthComponentReport_default_instance_._instance, + &::mavsdk::rpc::events::_HealthAndArmingCheckReport_default_instance_._instance, + &::mavsdk::rpc::events::_EventsResult_default_instance_._instance, + &::mavsdk::rpc::events::_SubscribeEventsRequest_default_instance_._instance, + &::mavsdk::rpc::events::_EventsResponse_default_instance_._instance, + &::mavsdk::rpc::events::_SubscribeHealthAndArmingChecksRequest_default_instance_._instance, + &::mavsdk::rpc::events::_HealthAndArmingChecksResponse_default_instance_._instance, + &::mavsdk::rpc::events::_GetHealthAndArmingChecksReportRequest_default_instance_._instance, + &::mavsdk::rpc::events::_GetHealthAndArmingChecksReportResponse_default_instance_._instance, +}; +const char descriptor_table_protodef_events_2fevents_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + "\n\023events/events.proto\022\021mavsdk.rpc.events" + "\032\024mavsdk_options.proto\"\232\001\n\005Event\022\016\n\006comp" + "id\030\001 \001(\r\022\017\n\007message\030\002 \001(\t\022\023\n\013description" + "\030\003 \001(\t\022.\n\tlog_level\030\004 \001(\0162\033.mavsdk.rpc.e" + "vents.LogLevel\022\027\n\017event_namespace\030\005 \001(\t\022" + "\022\n\nevent_name\030\006 \001(\t\"\215\001\n\033HealthAndArmingC" + "heckProblem\022\017\n\007message\030\001 \001(\t\022\023\n\013descript" + "ion\030\002 \001(\t\022.\n\tlog_level\030\003 \001(\0162\033.mavsdk.rp" + "c.events.LogLevel\022\030\n\020health_component\030\004 " + "\001(\t\"\207\001\n\030HealthAndArmingCheckMode\022\021\n\tmode" + "_name\030\001 \001(\t\022\026\n\016can_arm_or_run\030\002 \001(\010\022@\n\010p" + "roblems\030\003 \003(\0132..mavsdk.rpc.events.Health" + "AndArmingCheckProblem\"p\n\025HealthComponent" + "Report\022\014\n\004name\030\001 \001(\t\022\r\n\005label\030\002 \001(\t\022\022\n\ni" + "s_present\030\003 \001(\010\022\021\n\thas_error\030\004 \001(\010\022\023\n\013ha" + "s_warning\030\005 \001(\010\"\364\001\n\032HealthAndArmingCheck" + "Report\022K\n\026current_mode_intention\030\001 \001(\0132+" + ".mavsdk.rpc.events.HealthAndArmingCheckM" + "ode\022C\n\021health_components\030\002 \003(\0132(.mavsdk." + "rpc.events.HealthComponentReport\022D\n\014all_" + "problems\030\003 \003(\0132..mavsdk.rpc.events.Healt" + "hAndArmingCheckProblem\"\230\002\n\014EventsResult\022" + "6\n\006result\030\001 \001(\0162&.mavsdk.rpc.events.Even" + "tsResult.Result\022\022\n\nresult_str\030\002 \001(\t\"\273\001\n\006" + "Result\022\022\n\016RESULT_SUCCESS\020\000\022\030\n\024RESULT_NOT" + "_AVAILABLE\020\001\022\033\n\027RESULT_CONNECTION_ERROR\020" + "\002\022\026\n\022RESULT_UNSUPPORTED\020\003\022\021\n\rRESULT_DENI" + "ED\020\004\022\021\n\rRESULT_FAILED\020\005\022\022\n\016RESULT_TIMEOU" + "T\020\006\022\024\n\020RESULT_NO_SYSTEM\020\007\"\030\n\026SubscribeEv" + "entsRequest\"9\n\016EventsResponse\022\'\n\005event\030\001" + " \001(\0132\030.mavsdk.rpc.events.Event\"\'\n%Subscr" + "ibeHealthAndArmingChecksRequest\"^\n\035Healt" + "hAndArmingChecksResponse\022=\n\006report\030\001 \001(\013" + "2-.mavsdk.rpc.events.HealthAndArmingChec" + "kReport\"\'\n%GetHealthAndArmingChecksRepor" + "tRequest\"\237\001\n&GetHealthAndArmingChecksRep" + "ortResponse\0226\n\revents_result\030\001 \001(\0132\037.mav" + "sdk.rpc.events.EventsResult\022=\n\006report\030\002 " + "\001(\0132-.mavsdk.rpc.events.HealthAndArmingC" + "heckReport*\273\001\n\010LogLevel\022\027\n\023LOG_LEVEL_EME" + "RGENCY\020\000\022\023\n\017LOG_LEVEL_ALERT\020\001\022\026\n\022LOG_LEV" + "EL_CRITICAL\020\002\022\023\n\017LOG_LEVEL_ERROR\020\003\022\025\n\021LO" + "G_LEVEL_WARNING\020\004\022\024\n\020LOG_LEVEL_NOTICE\020\005\022" + "\022\n\016LOG_LEVEL_INFO\020\006\022\023\n\017LOG_LEVEL_DEBUG\020\007" + "2\255\003\n\rEventsService\022g\n\017SubscribeEvents\022)." + "mavsdk.rpc.events.SubscribeEventsRequest" + "\032!.mavsdk.rpc.events.EventsResponse\"\004\200\265\030" + "\0000\001\022\224\001\n\036SubscribeHealthAndArmingChecks\0228" + ".mavsdk.rpc.events.SubscribeHealthAndArm" + "ingChecksRequest\0320.mavsdk.rpc.events.Hea" + "lthAndArmingChecksResponse\"\004\200\265\030\0000\001\022\233\001\n\036G" + "etHealthAndArmingChecksReport\0228.mavsdk.r" + "pc.events.GetHealthAndArmingChecksReport" + "Request\0329.mavsdk.rpc.events.GetHealthAnd" + "ArmingChecksReportResponse\"\004\200\265\030\001B\037\n\020io.m" + "avsdk.eventsB\013EventsProtob\006proto3" +}; +static const ::_pbi::DescriptorTable* const descriptor_table_events_2fevents_2eproto_deps[1] = + { + &::descriptor_table_mavsdk_5foptions_2eproto, +}; +static ::absl::once_flag descriptor_table_events_2fevents_2eproto_once; +const ::_pbi::DescriptorTable descriptor_table_events_2fevents_2eproto = { + false, + false, + 2233, + descriptor_table_protodef_events_2fevents_2eproto, + "events/events.proto", + &descriptor_table_events_2fevents_2eproto_once, + descriptor_table_events_2fevents_2eproto_deps, + 1, + 12, + schemas, + file_default_instances, + TableStruct_events_2fevents_2eproto::offsets, + file_level_metadata_events_2fevents_2eproto, + file_level_enum_descriptors_events_2fevents_2eproto, + file_level_service_descriptors_events_2fevents_2eproto, +}; + +// This function exists to be marked as weak. +// It can significantly speed up compilation by breaking up LLVM's SCC +// in the .pb.cc translation units. Large translation units see a +// reduction of more than 35% of walltime for optimized builds. Without +// the weak attribute all the messages in the file, including all the +// vtables and everything they use become part of the same SCC through +// a cycle like: +// GetMetadata -> descriptor table -> default instances -> +// vtables -> GetMetadata +// By adding a weak function here we break the connection from the +// individual vtables back into the descriptor table. +PROTOBUF_ATTRIBUTE_WEAK const ::_pbi::DescriptorTable* descriptor_table_events_2fevents_2eproto_getter() { + return &descriptor_table_events_2fevents_2eproto; +} +// Force running AddDescriptors() at dynamic initialization time. +PROTOBUF_ATTRIBUTE_INIT_PRIORITY2 +static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_events_2fevents_2eproto(&descriptor_table_events_2fevents_2eproto); +namespace mavsdk { +namespace rpc { +namespace events { +const ::google::protobuf::EnumDescriptor* EventsResult_Result_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_events_2fevents_2eproto); + return file_level_enum_descriptors_events_2fevents_2eproto[0]; +} +PROTOBUF_CONSTINIT const uint32_t EventsResult_Result_internal_data_[] = { + 524288u, 0u, }; +bool EventsResult_Result_IsValid(int value) { + return 0 <= value && value <= 7; +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr EventsResult_Result EventsResult::RESULT_SUCCESS; +constexpr EventsResult_Result EventsResult::RESULT_NOT_AVAILABLE; +constexpr EventsResult_Result EventsResult::RESULT_CONNECTION_ERROR; +constexpr EventsResult_Result EventsResult::RESULT_UNSUPPORTED; +constexpr EventsResult_Result EventsResult::RESULT_DENIED; +constexpr EventsResult_Result EventsResult::RESULT_FAILED; +constexpr EventsResult_Result EventsResult::RESULT_TIMEOUT; +constexpr EventsResult_Result EventsResult::RESULT_NO_SYSTEM; +constexpr EventsResult_Result EventsResult::Result_MIN; +constexpr EventsResult_Result EventsResult::Result_MAX; +constexpr int EventsResult::Result_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::google::protobuf::EnumDescriptor* LogLevel_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_events_2fevents_2eproto); + return file_level_enum_descriptors_events_2fevents_2eproto[1]; +} +PROTOBUF_CONSTINIT const uint32_t LogLevel_internal_data_[] = { + 524288u, 0u, }; +bool LogLevel_IsValid(int value) { + return 0 <= value && value <= 7; +} +// =================================================================== + +class Event::_Internal { + public: +}; + +Event::Event(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.Event) +} +inline PROTOBUF_NDEBUG_INLINE Event::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : message_(arena, from.message_), + description_(arena, from.description_), + event_namespace_(arena, from.event_namespace_), + event_name_(arena, from.event_name_), + _cached_size_{0} {} + +Event::Event( + ::google::protobuf::Arena* arena, + const Event& from) + : ::google::protobuf::Message(arena) { + Event* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::memcpy(reinterpret_cast(&_impl_) + + offsetof(Impl_, compid_), + reinterpret_cast(&from._impl_) + + offsetof(Impl_, compid_), + offsetof(Impl_, log_level_) - + offsetof(Impl_, compid_) + + sizeof(Impl_::log_level_)); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.Event) +} +inline PROTOBUF_NDEBUG_INLINE Event::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : message_(arena), + description_(arena), + event_namespace_(arena), + event_name_(arena), + _cached_size_{0} {} + +inline void Event::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, compid_), + 0, + offsetof(Impl_, log_level_) - + offsetof(Impl_, compid_) + + sizeof(Impl_::log_level_)); +} +Event::~Event() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.Event) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void Event::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.message_.Destroy(); + _impl_.description_.Destroy(); + _impl_.event_namespace_.Destroy(); + _impl_.event_name_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void Event::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.Event) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.message_.ClearToEmpty(); + _impl_.description_.ClearToEmpty(); + _impl_.event_namespace_.ClearToEmpty(); + _impl_.event_name_.ClearToEmpty(); + ::memset(&_impl_.compid_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.log_level_) - + reinterpret_cast(&_impl_.compid_)) + sizeof(_impl_.log_level_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* Event::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<3, 6, 0, 75, 2> Event::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 6, 56, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967232, // skipmap + offsetof(decltype(_table_), field_entries), + 6, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_Event_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // uint32 compid = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Event, _impl_.compid_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(Event, _impl_.compid_)}}, + // string message = 2; + {::_pbi::TcParser::FastUS1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(Event, _impl_.message_)}}, + // string description = 3; + {::_pbi::TcParser::FastUS1, + {26, 63, 0, PROTOBUF_FIELD_OFFSET(Event, _impl_.description_)}}, + // .mavsdk.rpc.events.LogLevel log_level = 4; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Event, _impl_.log_level_), 63>(), + {32, 63, 0, PROTOBUF_FIELD_OFFSET(Event, _impl_.log_level_)}}, + // string event_namespace = 5; + {::_pbi::TcParser::FastUS1, + {42, 63, 0, PROTOBUF_FIELD_OFFSET(Event, _impl_.event_namespace_)}}, + // string event_name = 6; + {::_pbi::TcParser::FastUS1, + {50, 63, 0, PROTOBUF_FIELD_OFFSET(Event, _impl_.event_name_)}}, + {::_pbi::TcParser::MiniParse, {}}, + }}, {{ + 65535, 65535 + }}, {{ + // uint32 compid = 1; + {PROTOBUF_FIELD_OFFSET(Event, _impl_.compid_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // string message = 2; + {PROTOBUF_FIELD_OFFSET(Event, _impl_.message_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // string description = 3; + {PROTOBUF_FIELD_OFFSET(Event, _impl_.description_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // .mavsdk.rpc.events.LogLevel log_level = 4; + {PROTOBUF_FIELD_OFFSET(Event, _impl_.log_level_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + // string event_namespace = 5; + {PROTOBUF_FIELD_OFFSET(Event, _impl_.event_namespace_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // string event_name = 6; + {PROTOBUF_FIELD_OFFSET(Event, _impl_.event_name_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\27\0\7\13\0\17\12\0" + "mavsdk.rpc.events.Event" + "message" + "description" + "event_namespace" + "event_name" + }}, +}; + +::uint8_t* Event::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.Event) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // uint32 compid = 1; + if (this->_internal_compid() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 1, this->_internal_compid(), target); + } + + // string message = 2; + if (!this->_internal_message().empty()) { + const std::string& _s = this->_internal_message(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.Event.message"); + target = stream->WriteStringMaybeAliased(2, _s, target); + } + + // string description = 3; + if (!this->_internal_description().empty()) { + const std::string& _s = this->_internal_description(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.Event.description"); + target = stream->WriteStringMaybeAliased(3, _s, target); + } + + // .mavsdk.rpc.events.LogLevel log_level = 4; + if (this->_internal_log_level() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 4, this->_internal_log_level(), target); + } + + // string event_namespace = 5; + if (!this->_internal_event_namespace().empty()) { + const std::string& _s = this->_internal_event_namespace(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.Event.event_namespace"); + target = stream->WriteStringMaybeAliased(5, _s, target); + } + + // string event_name = 6; + if (!this->_internal_event_name().empty()) { + const std::string& _s = this->_internal_event_name(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.Event.event_name"); + target = stream->WriteStringMaybeAliased(6, _s, target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.Event) + return target; +} + +::size_t Event::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.Event) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string message = 2; + if (!this->_internal_message().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_message()); + } + + // string description = 3; + if (!this->_internal_description().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_description()); + } + + // string event_namespace = 5; + if (!this->_internal_event_namespace().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_event_namespace()); + } + + // string event_name = 6; + if (!this->_internal_event_name().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_event_name()); + } + + // uint32 compid = 1; + if (this->_internal_compid() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_compid()); + } + + // .mavsdk.rpc.events.LogLevel log_level = 4; + if (this->_internal_log_level() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_log_level()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData Event::_class_data_ = { + Event::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* Event::GetClassData() const { + return &_class_data_; +} + +void Event::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.Event) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_message().empty()) { + _this->_internal_set_message(from._internal_message()); + } + if (!from._internal_description().empty()) { + _this->_internal_set_description(from._internal_description()); + } + if (!from._internal_event_namespace().empty()) { + _this->_internal_set_event_namespace(from._internal_event_namespace()); + } + if (!from._internal_event_name().empty()) { + _this->_internal_set_event_name(from._internal_event_name()); + } + if (from._internal_compid() != 0) { + _this->_internal_set_compid(from._internal_compid()); + } + if (from._internal_log_level() != 0) { + _this->_internal_set_log_level(from._internal_log_level()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void Event::CopyFrom(const Event& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.Event) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool Event::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* Event::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void Event::InternalSwap(Event* PROTOBUF_RESTRICT other) { + using std::swap; + auto* arena = GetArena(); + ABSL_DCHECK_EQ(arena, other->GetArena()); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.message_, &other->_impl_.message_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.description_, &other->_impl_.description_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.event_namespace_, &other->_impl_.event_namespace_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.event_name_, &other->_impl_.event_name_, arena); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(Event, _impl_.log_level_) + + sizeof(Event::_impl_.log_level_) + - PROTOBUF_FIELD_OFFSET(Event, _impl_.compid_)>( + reinterpret_cast(&_impl_.compid_), + reinterpret_cast(&other->_impl_.compid_)); +} + +::google::protobuf::Metadata Event::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[0]); +} +// =================================================================== + +class HealthAndArmingCheckProblem::_Internal { + public: +}; + +HealthAndArmingCheckProblem::HealthAndArmingCheckProblem(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.HealthAndArmingCheckProblem) +} +inline PROTOBUF_NDEBUG_INLINE HealthAndArmingCheckProblem::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : message_(arena, from.message_), + description_(arena, from.description_), + health_component_(arena, from.health_component_), + _cached_size_{0} {} + +HealthAndArmingCheckProblem::HealthAndArmingCheckProblem( + ::google::protobuf::Arena* arena, + const HealthAndArmingCheckProblem& from) + : ::google::protobuf::Message(arena) { + HealthAndArmingCheckProblem* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + _impl_.log_level_ = from._impl_.log_level_; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.HealthAndArmingCheckProblem) +} +inline PROTOBUF_NDEBUG_INLINE HealthAndArmingCheckProblem::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : message_(arena), + description_(arena), + health_component_(arena), + _cached_size_{0} {} + +inline void HealthAndArmingCheckProblem::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.log_level_ = {}; +} +HealthAndArmingCheckProblem::~HealthAndArmingCheckProblem() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.HealthAndArmingCheckProblem) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void HealthAndArmingCheckProblem::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.message_.Destroy(); + _impl_.description_.Destroy(); + _impl_.health_component_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void HealthAndArmingCheckProblem::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.HealthAndArmingCheckProblem) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.message_.ClearToEmpty(); + _impl_.description_.ClearToEmpty(); + _impl_.health_component_.ClearToEmpty(); + _impl_.log_level_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* HealthAndArmingCheckProblem::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<2, 4, 0, 88, 2> HealthAndArmingCheckProblem::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 4, 24, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967280, // skipmap + offsetof(decltype(_table_), field_entries), + 4, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_HealthAndArmingCheckProblem_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // string health_component = 4; + {::_pbi::TcParser::FastUS1, + {34, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckProblem, _impl_.health_component_)}}, + // string message = 1; + {::_pbi::TcParser::FastUS1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckProblem, _impl_.message_)}}, + // string description = 2; + {::_pbi::TcParser::FastUS1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckProblem, _impl_.description_)}}, + // .mavsdk.rpc.events.LogLevel log_level = 3; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(HealthAndArmingCheckProblem, _impl_.log_level_), 63>(), + {24, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckProblem, _impl_.log_level_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // string message = 1; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckProblem, _impl_.message_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // string description = 2; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckProblem, _impl_.description_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // .mavsdk.rpc.events.LogLevel log_level = 3; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckProblem, _impl_.log_level_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + // string health_component = 4; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckProblem, _impl_.health_component_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\55\7\13\0\20\0\0\0" + "mavsdk.rpc.events.HealthAndArmingCheckProblem" + "message" + "description" + "health_component" + }}, +}; + +::uint8_t* HealthAndArmingCheckProblem::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.HealthAndArmingCheckProblem) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // string message = 1; + if (!this->_internal_message().empty()) { + const std::string& _s = this->_internal_message(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.HealthAndArmingCheckProblem.message"); + target = stream->WriteStringMaybeAliased(1, _s, target); + } + + // string description = 2; + if (!this->_internal_description().empty()) { + const std::string& _s = this->_internal_description(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.HealthAndArmingCheckProblem.description"); + target = stream->WriteStringMaybeAliased(2, _s, target); + } + + // .mavsdk.rpc.events.LogLevel log_level = 3; + if (this->_internal_log_level() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 3, this->_internal_log_level(), target); + } + + // string health_component = 4; + if (!this->_internal_health_component().empty()) { + const std::string& _s = this->_internal_health_component(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.HealthAndArmingCheckProblem.health_component"); + target = stream->WriteStringMaybeAliased(4, _s, target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.HealthAndArmingCheckProblem) + return target; +} + +::size_t HealthAndArmingCheckProblem::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.HealthAndArmingCheckProblem) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string message = 1; + if (!this->_internal_message().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_message()); + } + + // string description = 2; + if (!this->_internal_description().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_description()); + } + + // string health_component = 4; + if (!this->_internal_health_component().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_health_component()); + } + + // .mavsdk.rpc.events.LogLevel log_level = 3; + if (this->_internal_log_level() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_log_level()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData HealthAndArmingCheckProblem::_class_data_ = { + HealthAndArmingCheckProblem::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* HealthAndArmingCheckProblem::GetClassData() const { + return &_class_data_; +} + +void HealthAndArmingCheckProblem::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.HealthAndArmingCheckProblem) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_message().empty()) { + _this->_internal_set_message(from._internal_message()); + } + if (!from._internal_description().empty()) { + _this->_internal_set_description(from._internal_description()); + } + if (!from._internal_health_component().empty()) { + _this->_internal_set_health_component(from._internal_health_component()); + } + if (from._internal_log_level() != 0) { + _this->_internal_set_log_level(from._internal_log_level()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void HealthAndArmingCheckProblem::CopyFrom(const HealthAndArmingCheckProblem& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.HealthAndArmingCheckProblem) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool HealthAndArmingCheckProblem::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* HealthAndArmingCheckProblem::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void HealthAndArmingCheckProblem::InternalSwap(HealthAndArmingCheckProblem* PROTOBUF_RESTRICT other) { + using std::swap; + auto* arena = GetArena(); + ABSL_DCHECK_EQ(arena, other->GetArena()); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.message_, &other->_impl_.message_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.description_, &other->_impl_.description_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.health_component_, &other->_impl_.health_component_, arena); + swap(_impl_.log_level_, other->_impl_.log_level_); +} + +::google::protobuf::Metadata HealthAndArmingCheckProblem::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[1]); +} +// =================================================================== + +class HealthAndArmingCheckMode::_Internal { + public: +}; + +HealthAndArmingCheckMode::HealthAndArmingCheckMode(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.HealthAndArmingCheckMode) +} +inline PROTOBUF_NDEBUG_INLINE HealthAndArmingCheckMode::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : problems_{visibility, arena, from.problems_}, + mode_name_(arena, from.mode_name_), + _cached_size_{0} {} + +HealthAndArmingCheckMode::HealthAndArmingCheckMode( + ::google::protobuf::Arena* arena, + const HealthAndArmingCheckMode& from) + : ::google::protobuf::Message(arena) { + HealthAndArmingCheckMode* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + _impl_.can_arm_or_run_ = from._impl_.can_arm_or_run_; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.HealthAndArmingCheckMode) +} +inline PROTOBUF_NDEBUG_INLINE HealthAndArmingCheckMode::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : problems_{visibility, arena}, + mode_name_(arena), + _cached_size_{0} {} + +inline void HealthAndArmingCheckMode::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.can_arm_or_run_ = {}; +} +HealthAndArmingCheckMode::~HealthAndArmingCheckMode() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.HealthAndArmingCheckMode) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void HealthAndArmingCheckMode::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.mode_name_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void HealthAndArmingCheckMode::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.HealthAndArmingCheckMode) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.problems_.Clear(); + _impl_.mode_name_.ClearToEmpty(); + _impl_.can_arm_or_run_ = false; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* HealthAndArmingCheckMode::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<2, 3, 1, 60, 2> HealthAndArmingCheckMode::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 3, 24, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967288, // skipmap + offsetof(decltype(_table_), field_entries), + 3, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_HealthAndArmingCheckMode_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // string mode_name = 1; + {::_pbi::TcParser::FastUS1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckMode, _impl_.mode_name_)}}, + // bool can_arm_or_run = 2; + {::_pbi::TcParser::SingularVarintNoZag1(), + {16, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckMode, _impl_.can_arm_or_run_)}}, + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem problems = 3; + {::_pbi::TcParser::FastMtR1, + {26, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckMode, _impl_.problems_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // string mode_name = 1; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckMode, _impl_.mode_name_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // bool can_arm_or_run = 2; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckMode, _impl_.can_arm_or_run_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kBool)}, + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem problems = 3; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckMode, _impl_.problems_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::events::HealthAndArmingCheckProblem>()}, + }}, {{ + "\52\11\0\0\0\0\0\0" + "mavsdk.rpc.events.HealthAndArmingCheckMode" + "mode_name" + }}, +}; + +::uint8_t* HealthAndArmingCheckMode::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.HealthAndArmingCheckMode) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // string mode_name = 1; + if (!this->_internal_mode_name().empty()) { + const std::string& _s = this->_internal_mode_name(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.HealthAndArmingCheckMode.mode_name"); + target = stream->WriteStringMaybeAliased(1, _s, target); + } + + // bool can_arm_or_run = 2; + if (this->_internal_can_arm_or_run() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 2, this->_internal_can_arm_or_run(), target); + } + + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem problems = 3; + for (unsigned i = 0, + n = static_cast(this->_internal_problems_size()); i < n; i++) { + const auto& repfield = this->_internal_problems().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(3, repfield, repfield.GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.HealthAndArmingCheckMode) + return target; +} + +::size_t HealthAndArmingCheckMode::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.HealthAndArmingCheckMode) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem problems = 3; + total_size += 1UL * this->_internal_problems_size(); + for (const auto& msg : this->_internal_problems()) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); + } + // string mode_name = 1; + if (!this->_internal_mode_name().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_mode_name()); + } + + // bool can_arm_or_run = 2; + if (this->_internal_can_arm_or_run() != 0) { + total_size += 2; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData HealthAndArmingCheckMode::_class_data_ = { + HealthAndArmingCheckMode::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* HealthAndArmingCheckMode::GetClassData() const { + return &_class_data_; +} + +void HealthAndArmingCheckMode::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.HealthAndArmingCheckMode) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + _this->_internal_mutable_problems()->MergeFrom( + from._internal_problems()); + if (!from._internal_mode_name().empty()) { + _this->_internal_set_mode_name(from._internal_mode_name()); + } + if (from._internal_can_arm_or_run() != 0) { + _this->_internal_set_can_arm_or_run(from._internal_can_arm_or_run()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void HealthAndArmingCheckMode::CopyFrom(const HealthAndArmingCheckMode& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.HealthAndArmingCheckMode) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool HealthAndArmingCheckMode::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* HealthAndArmingCheckMode::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void HealthAndArmingCheckMode::InternalSwap(HealthAndArmingCheckMode* PROTOBUF_RESTRICT other) { + using std::swap; + auto* arena = GetArena(); + ABSL_DCHECK_EQ(arena, other->GetArena()); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + _impl_.problems_.InternalSwap(&other->_impl_.problems_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.mode_name_, &other->_impl_.mode_name_, arena); + swap(_impl_.can_arm_or_run_, other->_impl_.can_arm_or_run_); +} + +::google::protobuf::Metadata HealthAndArmingCheckMode::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[2]); +} +// =================================================================== + +class HealthComponentReport::_Internal { + public: +}; + +HealthComponentReport::HealthComponentReport(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.HealthComponentReport) +} +inline PROTOBUF_NDEBUG_INLINE HealthComponentReport::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : name_(arena, from.name_), + label_(arena, from.label_), + _cached_size_{0} {} + +HealthComponentReport::HealthComponentReport( + ::google::protobuf::Arena* arena, + const HealthComponentReport& from) + : ::google::protobuf::Message(arena) { + HealthComponentReport* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::memcpy(reinterpret_cast(&_impl_) + + offsetof(Impl_, is_present_), + reinterpret_cast(&from._impl_) + + offsetof(Impl_, is_present_), + offsetof(Impl_, has_warning_) - + offsetof(Impl_, is_present_) + + sizeof(Impl_::has_warning_)); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.HealthComponentReport) +} +inline PROTOBUF_NDEBUG_INLINE HealthComponentReport::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : name_(arena), + label_(arena), + _cached_size_{0} {} + +inline void HealthComponentReport::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, is_present_), + 0, + offsetof(Impl_, has_warning_) - + offsetof(Impl_, is_present_) + + sizeof(Impl_::has_warning_)); +} +HealthComponentReport::~HealthComponentReport() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.HealthComponentReport) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void HealthComponentReport::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.name_.Destroy(); + _impl_.label_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void HealthComponentReport::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.HealthComponentReport) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.name_.ClearToEmpty(); + _impl_.label_.ClearToEmpty(); + ::memset(&_impl_.is_present_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.has_warning_) - + reinterpret_cast(&_impl_.is_present_)) + sizeof(_impl_.has_warning_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* HealthComponentReport::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<3, 5, 0, 57, 2> HealthComponentReport::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 5, 56, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967264, // skipmap + offsetof(decltype(_table_), field_entries), + 5, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_HealthComponentReport_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // string name = 1; + {::_pbi::TcParser::FastUS1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.name_)}}, + // string label = 2; + {::_pbi::TcParser::FastUS1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.label_)}}, + // bool is_present = 3; + {::_pbi::TcParser::SingularVarintNoZag1(), + {24, 63, 0, PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.is_present_)}}, + // bool has_error = 4; + {::_pbi::TcParser::SingularVarintNoZag1(), + {32, 63, 0, PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.has_error_)}}, + // bool has_warning = 5; + {::_pbi::TcParser::SingularVarintNoZag1(), + {40, 63, 0, PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.has_warning_)}}, + {::_pbi::TcParser::MiniParse, {}}, + {::_pbi::TcParser::MiniParse, {}}, + }}, {{ + 65535, 65535 + }}, {{ + // string name = 1; + {PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.name_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // string label = 2; + {PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.label_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // bool is_present = 3; + {PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.is_present_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kBool)}, + // bool has_error = 4; + {PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.has_error_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kBool)}, + // bool has_warning = 5; + {PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.has_warning_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kBool)}, + }}, + // no aux_entries + {{ + "\47\4\5\0\0\0\0\0" + "mavsdk.rpc.events.HealthComponentReport" + "name" + "label" + }}, +}; + +::uint8_t* HealthComponentReport::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.HealthComponentReport) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // string name = 1; + if (!this->_internal_name().empty()) { + const std::string& _s = this->_internal_name(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.HealthComponentReport.name"); + target = stream->WriteStringMaybeAliased(1, _s, target); + } + + // string label = 2; + if (!this->_internal_label().empty()) { + const std::string& _s = this->_internal_label(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.HealthComponentReport.label"); + target = stream->WriteStringMaybeAliased(2, _s, target); + } + + // bool is_present = 3; + if (this->_internal_is_present() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 3, this->_internal_is_present(), target); + } + + // bool has_error = 4; + if (this->_internal_has_error() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 4, this->_internal_has_error(), target); + } + + // bool has_warning = 5; + if (this->_internal_has_warning() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 5, this->_internal_has_warning(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.HealthComponentReport) + return target; +} + +::size_t HealthComponentReport::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.HealthComponentReport) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string name = 1; + if (!this->_internal_name().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_name()); + } + + // string label = 2; + if (!this->_internal_label().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_label()); + } + + // bool is_present = 3; + if (this->_internal_is_present() != 0) { + total_size += 2; + } + + // bool has_error = 4; + if (this->_internal_has_error() != 0) { + total_size += 2; + } + + // bool has_warning = 5; + if (this->_internal_has_warning() != 0) { + total_size += 2; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData HealthComponentReport::_class_data_ = { + HealthComponentReport::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* HealthComponentReport::GetClassData() const { + return &_class_data_; +} + +void HealthComponentReport::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.HealthComponentReport) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_name().empty()) { + _this->_internal_set_name(from._internal_name()); + } + if (!from._internal_label().empty()) { + _this->_internal_set_label(from._internal_label()); + } + if (from._internal_is_present() != 0) { + _this->_internal_set_is_present(from._internal_is_present()); + } + if (from._internal_has_error() != 0) { + _this->_internal_set_has_error(from._internal_has_error()); + } + if (from._internal_has_warning() != 0) { + _this->_internal_set_has_warning(from._internal_has_warning()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void HealthComponentReport::CopyFrom(const HealthComponentReport& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.HealthComponentReport) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool HealthComponentReport::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* HealthComponentReport::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void HealthComponentReport::InternalSwap(HealthComponentReport* PROTOBUF_RESTRICT other) { + using std::swap; + auto* arena = GetArena(); + ABSL_DCHECK_EQ(arena, other->GetArena()); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.name_, &other->_impl_.name_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.label_, &other->_impl_.label_, arena); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.has_warning_) + + sizeof(HealthComponentReport::_impl_.has_warning_) + - PROTOBUF_FIELD_OFFSET(HealthComponentReport, _impl_.is_present_)>( + reinterpret_cast(&_impl_.is_present_), + reinterpret_cast(&other->_impl_.is_present_)); +} + +::google::protobuf::Metadata HealthComponentReport::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[3]); +} +// =================================================================== + +class HealthAndArmingCheckReport::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckReport, _impl_._has_bits_); + static const ::mavsdk::rpc::events::HealthAndArmingCheckMode& current_mode_intention(const HealthAndArmingCheckReport* msg); + static void set_has_current_mode_intention(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::events::HealthAndArmingCheckMode& HealthAndArmingCheckReport::_Internal::current_mode_intention(const HealthAndArmingCheckReport* msg) { + return *msg->_impl_.current_mode_intention_; +} +HealthAndArmingCheckReport::HealthAndArmingCheckReport(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.HealthAndArmingCheckReport) +} +inline PROTOBUF_NDEBUG_INLINE HealthAndArmingCheckReport::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0}, + health_components_{visibility, arena, from.health_components_}, + all_problems_{visibility, arena, from.all_problems_} {} + +HealthAndArmingCheckReport::HealthAndArmingCheckReport( + ::google::protobuf::Arena* arena, + const HealthAndArmingCheckReport& from) + : ::google::protobuf::Message(arena) { + HealthAndArmingCheckReport* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.current_mode_intention_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::events::HealthAndArmingCheckMode>(arena, *from._impl_.current_mode_intention_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.HealthAndArmingCheckReport) +} +inline PROTOBUF_NDEBUG_INLINE HealthAndArmingCheckReport::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0}, + health_components_{visibility, arena}, + all_problems_{visibility, arena} {} + +inline void HealthAndArmingCheckReport::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.current_mode_intention_ = {}; +} +HealthAndArmingCheckReport::~HealthAndArmingCheckReport() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.HealthAndArmingCheckReport) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void HealthAndArmingCheckReport::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.current_mode_intention_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void HealthAndArmingCheckReport::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.HealthAndArmingCheckReport) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.health_components_.Clear(); + _impl_.all_problems_.Clear(); + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.current_mode_intention_ != nullptr); + _impl_.current_mode_intention_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* HealthAndArmingCheckReport::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<2, 3, 3, 0, 2> HealthAndArmingCheckReport::_table_ = { + { + PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckReport, _impl_._has_bits_), + 0, // no _extensions_ + 3, 24, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967288, // skipmap + offsetof(decltype(_table_), field_entries), + 3, // num_field_entries + 3, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_HealthAndArmingCheckReport_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // .mavsdk.rpc.events.HealthAndArmingCheckMode current_mode_intention = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckReport, _impl_.current_mode_intention_)}}, + // repeated .mavsdk.rpc.events.HealthComponentReport health_components = 2; + {::_pbi::TcParser::FastMtR1, + {18, 63, 1, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckReport, _impl_.health_components_)}}, + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem all_problems = 3; + {::_pbi::TcParser::FastMtR1, + {26, 63, 2, PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckReport, _impl_.all_problems_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.events.HealthAndArmingCheckMode current_mode_intention = 1; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckReport, _impl_.current_mode_intention_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // repeated .mavsdk.rpc.events.HealthComponentReport health_components = 2; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckReport, _impl_.health_components_), -1, 1, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem all_problems = 3; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingCheckReport, _impl_.all_problems_), -1, 2, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::events::HealthAndArmingCheckMode>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::events::HealthComponentReport>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::events::HealthAndArmingCheckProblem>()}, + }}, {{ + }}, +}; + +::uint8_t* HealthAndArmingCheckReport::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.HealthAndArmingCheckReport) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.events.HealthAndArmingCheckMode current_mode_intention = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::current_mode_intention(this), + _Internal::current_mode_intention(this).GetCachedSize(), target, stream); + } + + // repeated .mavsdk.rpc.events.HealthComponentReport health_components = 2; + for (unsigned i = 0, + n = static_cast(this->_internal_health_components_size()); i < n; i++) { + const auto& repfield = this->_internal_health_components().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(2, repfield, repfield.GetCachedSize(), target, stream); + } + + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem all_problems = 3; + for (unsigned i = 0, + n = static_cast(this->_internal_all_problems_size()); i < n; i++) { + const auto& repfield = this->_internal_all_problems().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(3, repfield, repfield.GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.HealthAndArmingCheckReport) + return target; +} + +::size_t HealthAndArmingCheckReport::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.HealthAndArmingCheckReport) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // repeated .mavsdk.rpc.events.HealthComponentReport health_components = 2; + total_size += 1UL * this->_internal_health_components_size(); + for (const auto& msg : this->_internal_health_components()) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); + } + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem all_problems = 3; + total_size += 1UL * this->_internal_all_problems_size(); + for (const auto& msg : this->_internal_all_problems()) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); + } + // .mavsdk.rpc.events.HealthAndArmingCheckMode current_mode_intention = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.current_mode_intention_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData HealthAndArmingCheckReport::_class_data_ = { + HealthAndArmingCheckReport::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* HealthAndArmingCheckReport::GetClassData() const { + return &_class_data_; +} + +void HealthAndArmingCheckReport::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.HealthAndArmingCheckReport) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + _this->_internal_mutable_health_components()->MergeFrom( + from._internal_health_components()); + _this->_internal_mutable_all_problems()->MergeFrom( + from._internal_all_problems()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_current_mode_intention()->::mavsdk::rpc::events::HealthAndArmingCheckMode::MergeFrom( + from._internal_current_mode_intention()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void HealthAndArmingCheckReport::CopyFrom(const HealthAndArmingCheckReport& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.HealthAndArmingCheckReport) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool HealthAndArmingCheckReport::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* HealthAndArmingCheckReport::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void HealthAndArmingCheckReport::InternalSwap(HealthAndArmingCheckReport* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + _impl_.health_components_.InternalSwap(&other->_impl_.health_components_); + _impl_.all_problems_.InternalSwap(&other->_impl_.all_problems_); + swap(_impl_.current_mode_intention_, other->_impl_.current_mode_intention_); +} + +::google::protobuf::Metadata HealthAndArmingCheckReport::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[4]); +} +// =================================================================== + +class EventsResult::_Internal { + public: +}; + +EventsResult::EventsResult(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.EventsResult) +} +inline PROTOBUF_NDEBUG_INLINE EventsResult::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : result_str_(arena, from.result_str_), + _cached_size_{0} {} + +EventsResult::EventsResult( + ::google::protobuf::Arena* arena, + const EventsResult& from) + : ::google::protobuf::Message(arena) { + EventsResult* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + _impl_.result_ = from._impl_.result_; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.EventsResult) +} +inline PROTOBUF_NDEBUG_INLINE EventsResult::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : result_str_(arena), + _cached_size_{0} {} + +inline void EventsResult::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.result_ = {}; +} +EventsResult::~EventsResult() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.EventsResult) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void EventsResult::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.result_str_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void EventsResult::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.EventsResult) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.result_str_.ClearToEmpty(); + _impl_.result_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* EventsResult::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<1, 2, 0, 49, 2> EventsResult::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 2, 8, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967292, // skipmap + offsetof(decltype(_table_), field_entries), + 2, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_EventsResult_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // string result_str = 2; + {::_pbi::TcParser::FastUS1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(EventsResult, _impl_.result_str_)}}, + // .mavsdk.rpc.events.EventsResult.Result result = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(EventsResult, _impl_.result_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(EventsResult, _impl_.result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.events.EventsResult.Result result = 1; + {PROTOBUF_FIELD_OFFSET(EventsResult, _impl_.result_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + // string result_str = 2; + {PROTOBUF_FIELD_OFFSET(EventsResult, _impl_.result_str_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\36\0\12\0\0\0\0\0" + "mavsdk.rpc.events.EventsResult" + "result_str" + }}, +}; + +::uint8_t* EventsResult::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.EventsResult) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // .mavsdk.rpc.events.EventsResult.Result result = 1; + if (this->_internal_result() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_result(), target); + } + + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + const std::string& _s = this->_internal_result_str(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.events.EventsResult.result_str"); + target = stream->WriteStringMaybeAliased(2, _s, target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.EventsResult) + return target; +} + +::size_t EventsResult::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.EventsResult) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_result_str()); + } + + // .mavsdk.rpc.events.EventsResult.Result result = 1; + if (this->_internal_result() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_result()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData EventsResult::_class_data_ = { + EventsResult::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* EventsResult::GetClassData() const { + return &_class_data_; +} + +void EventsResult::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.EventsResult) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_result_str().empty()) { + _this->_internal_set_result_str(from._internal_result_str()); + } + if (from._internal_result() != 0) { + _this->_internal_set_result(from._internal_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void EventsResult::CopyFrom(const EventsResult& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.EventsResult) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool EventsResult::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* EventsResult::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void EventsResult::InternalSwap(EventsResult* PROTOBUF_RESTRICT other) { + using std::swap; + auto* arena = GetArena(); + ABSL_DCHECK_EQ(arena, other->GetArena()); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.result_str_, &other->_impl_.result_str_, arena); + swap(_impl_.result_, other->_impl_.result_); +} + +::google::protobuf::Metadata EventsResult::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[5]); +} +// =================================================================== + +class SubscribeEventsRequest::_Internal { + public: +}; + +SubscribeEventsRequest::SubscribeEventsRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.SubscribeEventsRequest) +} +SubscribeEventsRequest::SubscribeEventsRequest( + ::google::protobuf::Arena* arena, + const SubscribeEventsRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeEventsRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.SubscribeEventsRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeEventsRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[6]); +} +// =================================================================== + +class EventsResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(EventsResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::events::Event& event(const EventsResponse* msg); + static void set_has_event(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::events::Event& EventsResponse::_Internal::event(const EventsResponse* msg) { + return *msg->_impl_.event_; +} +EventsResponse::EventsResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.EventsResponse) +} +inline PROTOBUF_NDEBUG_INLINE EventsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +EventsResponse::EventsResponse( + ::google::protobuf::Arena* arena, + const EventsResponse& from) + : ::google::protobuf::Message(arena) { + EventsResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.event_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::events::Event>(arena, *from._impl_.event_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.EventsResponse) +} +inline PROTOBUF_NDEBUG_INLINE EventsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void EventsResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.event_ = {}; +} +EventsResponse::~EventsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.EventsResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void EventsResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.event_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void EventsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.EventsResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.event_ != nullptr); + _impl_.event_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* EventsResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> EventsResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(EventsResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_EventsResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.events.Event event = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(EventsResponse, _impl_.event_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.events.Event event = 1; + {PROTOBUF_FIELD_OFFSET(EventsResponse, _impl_.event_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::events::Event>()}, + }}, {{ + }}, +}; + +::uint8_t* EventsResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.EventsResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.events.Event event = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::event(this), + _Internal::event(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.EventsResponse) + return target; +} + +::size_t EventsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.EventsResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.events.Event event = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.event_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData EventsResponse::_class_data_ = { + EventsResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* EventsResponse::GetClassData() const { + return &_class_data_; +} + +void EventsResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.EventsResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_event()->::mavsdk::rpc::events::Event::MergeFrom( + from._internal_event()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void EventsResponse::CopyFrom(const EventsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.EventsResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool EventsResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* EventsResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void EventsResponse::InternalSwap(EventsResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.event_, other->_impl_.event_); +} + +::google::protobuf::Metadata EventsResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[7]); +} +// =================================================================== + +class SubscribeHealthAndArmingChecksRequest::_Internal { + public: +}; + +SubscribeHealthAndArmingChecksRequest::SubscribeHealthAndArmingChecksRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.SubscribeHealthAndArmingChecksRequest) +} +SubscribeHealthAndArmingChecksRequest::SubscribeHealthAndArmingChecksRequest( + ::google::protobuf::Arena* arena, + const SubscribeHealthAndArmingChecksRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeHealthAndArmingChecksRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.SubscribeHealthAndArmingChecksRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeHealthAndArmingChecksRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[8]); +} +// =================================================================== + +class HealthAndArmingChecksResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(HealthAndArmingChecksResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::events::HealthAndArmingCheckReport& report(const HealthAndArmingChecksResponse* msg); + static void set_has_report(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::events::HealthAndArmingCheckReport& HealthAndArmingChecksResponse::_Internal::report(const HealthAndArmingChecksResponse* msg) { + return *msg->_impl_.report_; +} +HealthAndArmingChecksResponse::HealthAndArmingChecksResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.HealthAndArmingChecksResponse) +} +inline PROTOBUF_NDEBUG_INLINE HealthAndArmingChecksResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +HealthAndArmingChecksResponse::HealthAndArmingChecksResponse( + ::google::protobuf::Arena* arena, + const HealthAndArmingChecksResponse& from) + : ::google::protobuf::Message(arena) { + HealthAndArmingChecksResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.report_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::events::HealthAndArmingCheckReport>(arena, *from._impl_.report_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.HealthAndArmingChecksResponse) +} +inline PROTOBUF_NDEBUG_INLINE HealthAndArmingChecksResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void HealthAndArmingChecksResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.report_ = {}; +} +HealthAndArmingChecksResponse::~HealthAndArmingChecksResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.HealthAndArmingChecksResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void HealthAndArmingChecksResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.report_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void HealthAndArmingChecksResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.HealthAndArmingChecksResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.report_ != nullptr); + _impl_.report_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* HealthAndArmingChecksResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> HealthAndArmingChecksResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(HealthAndArmingChecksResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_HealthAndArmingChecksResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(HealthAndArmingChecksResponse, _impl_.report_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 1; + {PROTOBUF_FIELD_OFFSET(HealthAndArmingChecksResponse, _impl_.report_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::events::HealthAndArmingCheckReport>()}, + }}, {{ + }}, +}; + +::uint8_t* HealthAndArmingChecksResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.HealthAndArmingChecksResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::report(this), + _Internal::report(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.HealthAndArmingChecksResponse) + return target; +} + +::size_t HealthAndArmingChecksResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.HealthAndArmingChecksResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.report_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData HealthAndArmingChecksResponse::_class_data_ = { + HealthAndArmingChecksResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* HealthAndArmingChecksResponse::GetClassData() const { + return &_class_data_; +} + +void HealthAndArmingChecksResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.HealthAndArmingChecksResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_report()->::mavsdk::rpc::events::HealthAndArmingCheckReport::MergeFrom( + from._internal_report()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void HealthAndArmingChecksResponse::CopyFrom(const HealthAndArmingChecksResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.HealthAndArmingChecksResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool HealthAndArmingChecksResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* HealthAndArmingChecksResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void HealthAndArmingChecksResponse::InternalSwap(HealthAndArmingChecksResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.report_, other->_impl_.report_); +} + +::google::protobuf::Metadata HealthAndArmingChecksResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[9]); +} +// =================================================================== + +class GetHealthAndArmingChecksReportRequest::_Internal { + public: +}; + +GetHealthAndArmingChecksReportRequest::GetHealthAndArmingChecksReportRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.GetHealthAndArmingChecksReportRequest) +} +GetHealthAndArmingChecksReportRequest::GetHealthAndArmingChecksReportRequest( + ::google::protobuf::Arena* arena, + const GetHealthAndArmingChecksReportRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + GetHealthAndArmingChecksReportRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.GetHealthAndArmingChecksReportRequest) +} + + + + + + + + + +::google::protobuf::Metadata GetHealthAndArmingChecksReportRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[10]); +} +// =================================================================== + +class GetHealthAndArmingChecksReportResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(GetHealthAndArmingChecksReportResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::events::EventsResult& events_result(const GetHealthAndArmingChecksReportResponse* msg); + static void set_has_events_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } + static const ::mavsdk::rpc::events::HealthAndArmingCheckReport& report(const GetHealthAndArmingChecksReportResponse* msg); + static void set_has_report(HasBits* has_bits) { + (*has_bits)[0] |= 2u; + } +}; + +const ::mavsdk::rpc::events::EventsResult& GetHealthAndArmingChecksReportResponse::_Internal::events_result(const GetHealthAndArmingChecksReportResponse* msg) { + return *msg->_impl_.events_result_; +} +const ::mavsdk::rpc::events::HealthAndArmingCheckReport& GetHealthAndArmingChecksReportResponse::_Internal::report(const GetHealthAndArmingChecksReportResponse* msg) { + return *msg->_impl_.report_; +} +GetHealthAndArmingChecksReportResponse::GetHealthAndArmingChecksReportResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetHealthAndArmingChecksReportResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +GetHealthAndArmingChecksReportResponse::GetHealthAndArmingChecksReportResponse( + ::google::protobuf::Arena* arena, + const GetHealthAndArmingChecksReportResponse& from) + : ::google::protobuf::Message(arena) { + GetHealthAndArmingChecksReportResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.events_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::events::EventsResult>(arena, *from._impl_.events_result_) + : nullptr; + _impl_.report_ = (cached_has_bits & 0x00000002u) + ? CreateMaybeMessage<::mavsdk::rpc::events::HealthAndArmingCheckReport>(arena, *from._impl_.report_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetHealthAndArmingChecksReportResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void GetHealthAndArmingChecksReportResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, events_result_), + 0, + offsetof(Impl_, report_) - + offsetof(Impl_, events_result_) + + sizeof(Impl_::report_)); +} +GetHealthAndArmingChecksReportResponse::~GetHealthAndArmingChecksReportResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void GetHealthAndArmingChecksReportResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.events_result_; + delete _impl_.report_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void GetHealthAndArmingChecksReportResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.events_result_ != nullptr); + _impl_.events_result_->Clear(); + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(_impl_.report_ != nullptr); + _impl_.report_->Clear(); + } + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* GetHealthAndArmingChecksReportResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<1, 2, 2, 0, 2> GetHealthAndArmingChecksReportResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(GetHealthAndArmingChecksReportResponse, _impl_._has_bits_), + 0, // no _extensions_ + 2, 8, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967292, // skipmap + offsetof(decltype(_table_), field_entries), + 2, // num_field_entries + 2, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_GetHealthAndArmingChecksReportResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 2; + {::_pbi::TcParser::FastMtS1, + {18, 1, 1, PROTOBUF_FIELD_OFFSET(GetHealthAndArmingChecksReportResponse, _impl_.report_)}}, + // .mavsdk.rpc.events.EventsResult events_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetHealthAndArmingChecksReportResponse, _impl_.events_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.events.EventsResult events_result = 1; + {PROTOBUF_FIELD_OFFSET(GetHealthAndArmingChecksReportResponse, _impl_.events_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 2; + {PROTOBUF_FIELD_OFFSET(GetHealthAndArmingChecksReportResponse, _impl_.report_), _Internal::kHasBitsOffset + 1, 1, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::events::EventsResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::events::HealthAndArmingCheckReport>()}, + }}, {{ + }}, +}; + +::uint8_t* GetHealthAndArmingChecksReportResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.events.EventsResult events_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::events_result(this), + _Internal::events_result(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 2; + if (cached_has_bits & 0x00000002u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 2, _Internal::report(this), + _Internal::report(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) + return target; +} + +::size_t GetHealthAndArmingChecksReportResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + // .mavsdk.rpc.events.EventsResult events_result = 1; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.events_result_); + } + + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 2; + if (cached_has_bits & 0x00000002u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.report_); + } + + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData GetHealthAndArmingChecksReportResponse::_class_data_ = { + GetHealthAndArmingChecksReportResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* GetHealthAndArmingChecksReportResponse::GetClassData() const { + return &_class_data_; +} + +void GetHealthAndArmingChecksReportResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + _this->_internal_mutable_events_result()->::mavsdk::rpc::events::EventsResult::MergeFrom( + from._internal_events_result()); + } + if (cached_has_bits & 0x00000002u) { + _this->_internal_mutable_report()->::mavsdk::rpc::events::HealthAndArmingCheckReport::MergeFrom( + from._internal_report()); + } + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void GetHealthAndArmingChecksReportResponse::CopyFrom(const GetHealthAndArmingChecksReportResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool GetHealthAndArmingChecksReportResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* GetHealthAndArmingChecksReportResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void GetHealthAndArmingChecksReportResponse::InternalSwap(GetHealthAndArmingChecksReportResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(GetHealthAndArmingChecksReportResponse, _impl_.report_) + + sizeof(GetHealthAndArmingChecksReportResponse::_impl_.report_) + - PROTOBUF_FIELD_OFFSET(GetHealthAndArmingChecksReportResponse, _impl_.events_result_)>( + reinterpret_cast(&_impl_.events_result_), + reinterpret_cast(&other->_impl_.events_result_)); +} + +::google::protobuf::Metadata GetHealthAndArmingChecksReportResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_events_2fevents_2eproto_getter, &descriptor_table_events_2fevents_2eproto_once, + file_level_metadata_events_2fevents_2eproto[11]); +} +// @@protoc_insertion_point(namespace_scope) +} // namespace events +} // namespace rpc +} // namespace mavsdk +namespace google { +namespace protobuf { +} // namespace protobuf +} // namespace google +// @@protoc_insertion_point(global_scope) +#include "google/protobuf/port_undef.inc" diff --git a/src/mavsdk_server/src/generated/events/events.pb.h b/src/mavsdk_server/src/generated/events/events.pb.h new file mode 100644 index 000000000..be10f029c --- /dev/null +++ b/src/mavsdk_server/src/generated/events/events.pb.h @@ -0,0 +1,4026 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: events/events.proto +// Protobuf C++ Version: 4.25.1 + +#ifndef GOOGLE_PROTOBUF_INCLUDED_events_2fevents_2eproto_2epb_2eh +#define GOOGLE_PROTOBUF_INCLUDED_events_2fevents_2eproto_2epb_2eh + +#include +#include +#include +#include + +#include "google/protobuf/port_def.inc" +#if PROTOBUF_VERSION < 4025000 +#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 // PROTOBUF_VERSION + +#if 4025001 < 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 // PROTOBUF_MIN_PROTOC_VERSION +#include "google/protobuf/port_undef.inc" +#include "google/protobuf/io/coded_stream.h" +#include "google/protobuf/arena.h" +#include "google/protobuf/arenastring.h" +#include "google/protobuf/generated_message_bases.h" +#include "google/protobuf/generated_message_tctable_decl.h" +#include "google/protobuf/generated_message_util.h" +#include "google/protobuf/metadata_lite.h" +#include "google/protobuf/generated_message_reflection.h" +#include "google/protobuf/message.h" +#include "google/protobuf/repeated_field.h" // IWYU pragma: export +#include "google/protobuf/extension_set.h" // IWYU pragma: export +#include "google/protobuf/generated_enum_reflection.h" +#include "google/protobuf/unknown_field_set.h" +#include "mavsdk_options.pb.h" +// @@protoc_insertion_point(includes) + +// Must be included last. +#include "google/protobuf/port_def.inc" + +#define PROTOBUF_INTERNAL_EXPORT_events_2fevents_2eproto + +namespace google { +namespace protobuf { +namespace internal { +class AnyMetadata; +} // namespace internal +} // namespace protobuf +} // namespace google + +// Internal implementation detail -- do not use these members. +struct TableStruct_events_2fevents_2eproto { + static const ::uint32_t offsets[]; +}; +extern const ::google::protobuf::internal::DescriptorTable + descriptor_table_events_2fevents_2eproto; +namespace mavsdk { +namespace rpc { +namespace events { +class Event; +struct EventDefaultTypeInternal; +extern EventDefaultTypeInternal _Event_default_instance_; +class EventsResponse; +struct EventsResponseDefaultTypeInternal; +extern EventsResponseDefaultTypeInternal _EventsResponse_default_instance_; +class EventsResult; +struct EventsResultDefaultTypeInternal; +extern EventsResultDefaultTypeInternal _EventsResult_default_instance_; +class GetHealthAndArmingChecksReportRequest; +struct GetHealthAndArmingChecksReportRequestDefaultTypeInternal; +extern GetHealthAndArmingChecksReportRequestDefaultTypeInternal _GetHealthAndArmingChecksReportRequest_default_instance_; +class GetHealthAndArmingChecksReportResponse; +struct GetHealthAndArmingChecksReportResponseDefaultTypeInternal; +extern GetHealthAndArmingChecksReportResponseDefaultTypeInternal _GetHealthAndArmingChecksReportResponse_default_instance_; +class HealthAndArmingCheckMode; +struct HealthAndArmingCheckModeDefaultTypeInternal; +extern HealthAndArmingCheckModeDefaultTypeInternal _HealthAndArmingCheckMode_default_instance_; +class HealthAndArmingCheckProblem; +struct HealthAndArmingCheckProblemDefaultTypeInternal; +extern HealthAndArmingCheckProblemDefaultTypeInternal _HealthAndArmingCheckProblem_default_instance_; +class HealthAndArmingCheckReport; +struct HealthAndArmingCheckReportDefaultTypeInternal; +extern HealthAndArmingCheckReportDefaultTypeInternal _HealthAndArmingCheckReport_default_instance_; +class HealthAndArmingChecksResponse; +struct HealthAndArmingChecksResponseDefaultTypeInternal; +extern HealthAndArmingChecksResponseDefaultTypeInternal _HealthAndArmingChecksResponse_default_instance_; +class HealthComponentReport; +struct HealthComponentReportDefaultTypeInternal; +extern HealthComponentReportDefaultTypeInternal _HealthComponentReport_default_instance_; +class SubscribeEventsRequest; +struct SubscribeEventsRequestDefaultTypeInternal; +extern SubscribeEventsRequestDefaultTypeInternal _SubscribeEventsRequest_default_instance_; +class SubscribeHealthAndArmingChecksRequest; +struct SubscribeHealthAndArmingChecksRequestDefaultTypeInternal; +extern SubscribeHealthAndArmingChecksRequestDefaultTypeInternal _SubscribeHealthAndArmingChecksRequest_default_instance_; +} // namespace events +} // namespace rpc +} // namespace mavsdk +namespace google { +namespace protobuf { +} // namespace protobuf +} // namespace google + +namespace mavsdk { +namespace rpc { +namespace events { +enum EventsResult_Result : int { + EventsResult_Result_RESULT_SUCCESS = 0, + EventsResult_Result_RESULT_NOT_AVAILABLE = 1, + EventsResult_Result_RESULT_CONNECTION_ERROR = 2, + EventsResult_Result_RESULT_UNSUPPORTED = 3, + EventsResult_Result_RESULT_DENIED = 4, + EventsResult_Result_RESULT_FAILED = 5, + EventsResult_Result_RESULT_TIMEOUT = 6, + EventsResult_Result_RESULT_NO_SYSTEM = 7, + EventsResult_Result_EventsResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + EventsResult_Result_EventsResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool EventsResult_Result_IsValid(int value); +extern const uint32_t EventsResult_Result_internal_data_[]; +constexpr EventsResult_Result EventsResult_Result_Result_MIN = static_cast(0); +constexpr EventsResult_Result EventsResult_Result_Result_MAX = static_cast(7); +constexpr int EventsResult_Result_Result_ARRAYSIZE = 7 + 1; +const ::google::protobuf::EnumDescriptor* +EventsResult_Result_descriptor(); +template +const std::string& EventsResult_Result_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to Result_Name()."); + return EventsResult_Result_Name(static_cast(value)); +} +template <> +inline const std::string& EventsResult_Result_Name(EventsResult_Result value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool EventsResult_Result_Parse(absl::string_view name, EventsResult_Result* value) { + return ::google::protobuf::internal::ParseNamedEnum( + EventsResult_Result_descriptor(), name, value); +} +enum LogLevel : int { + LOG_LEVEL_EMERGENCY = 0, + LOG_LEVEL_ALERT = 1, + LOG_LEVEL_CRITICAL = 2, + LOG_LEVEL_ERROR = 3, + LOG_LEVEL_WARNING = 4, + LOG_LEVEL_NOTICE = 5, + LOG_LEVEL_INFO = 6, + LOG_LEVEL_DEBUG = 7, + LogLevel_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + LogLevel_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool LogLevel_IsValid(int value); +extern const uint32_t LogLevel_internal_data_[]; +constexpr LogLevel LogLevel_MIN = static_cast(0); +constexpr LogLevel LogLevel_MAX = static_cast(7); +constexpr int LogLevel_ARRAYSIZE = 7 + 1; +const ::google::protobuf::EnumDescriptor* +LogLevel_descriptor(); +template +const std::string& LogLevel_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to LogLevel_Name()."); + return LogLevel_Name(static_cast(value)); +} +template <> +inline const std::string& LogLevel_Name(LogLevel value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool LogLevel_Parse(absl::string_view name, LogLevel* value) { + return ::google::protobuf::internal::ParseNamedEnum( + LogLevel_descriptor(), name, value); +} + +// =================================================================== + + +// ------------------------------------------------------------------- + +class SubscribeHealthAndArmingChecksRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.SubscribeHealthAndArmingChecksRequest) */ { + public: + inline SubscribeHealthAndArmingChecksRequest() : SubscribeHealthAndArmingChecksRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeHealthAndArmingChecksRequest(::google::protobuf::internal::ConstantInitialized); + + inline SubscribeHealthAndArmingChecksRequest(const SubscribeHealthAndArmingChecksRequest& from) + : SubscribeHealthAndArmingChecksRequest(nullptr, from) {} + SubscribeHealthAndArmingChecksRequest(SubscribeHealthAndArmingChecksRequest&& from) noexcept + : SubscribeHealthAndArmingChecksRequest() { + *this = ::std::move(from); + } + + inline SubscribeHealthAndArmingChecksRequest& operator=(const SubscribeHealthAndArmingChecksRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeHealthAndArmingChecksRequest& operator=(SubscribeHealthAndArmingChecksRequest&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SubscribeHealthAndArmingChecksRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeHealthAndArmingChecksRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeHealthAndArmingChecksRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 8; + + friend void swap(SubscribeHealthAndArmingChecksRequest& a, SubscribeHealthAndArmingChecksRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeHealthAndArmingChecksRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeHealthAndArmingChecksRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeHealthAndArmingChecksRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeHealthAndArmingChecksRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeHealthAndArmingChecksRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.SubscribeHealthAndArmingChecksRequest"; + } + protected: + explicit SubscribeHealthAndArmingChecksRequest(::google::protobuf::Arena* arena); + SubscribeHealthAndArmingChecksRequest(::google::protobuf::Arena* arena, const SubscribeHealthAndArmingChecksRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.SubscribeHealthAndArmingChecksRequest) + private: + class _Internal; + + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + PROTOBUF_TSAN_DECLARE_MEMBER + }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class SubscribeEventsRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.SubscribeEventsRequest) */ { + public: + inline SubscribeEventsRequest() : SubscribeEventsRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeEventsRequest(::google::protobuf::internal::ConstantInitialized); + + inline SubscribeEventsRequest(const SubscribeEventsRequest& from) + : SubscribeEventsRequest(nullptr, from) {} + SubscribeEventsRequest(SubscribeEventsRequest&& from) noexcept + : SubscribeEventsRequest() { + *this = ::std::move(from); + } + + inline SubscribeEventsRequest& operator=(const SubscribeEventsRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeEventsRequest& operator=(SubscribeEventsRequest&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SubscribeEventsRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeEventsRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeEventsRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + friend void swap(SubscribeEventsRequest& a, SubscribeEventsRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeEventsRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeEventsRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeEventsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeEventsRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeEventsRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.SubscribeEventsRequest"; + } + protected: + explicit SubscribeEventsRequest(::google::protobuf::Arena* arena); + SubscribeEventsRequest(::google::protobuf::Arena* arena, const SubscribeEventsRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.SubscribeEventsRequest) + private: + class _Internal; + + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + PROTOBUF_TSAN_DECLARE_MEMBER + }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class HealthComponentReport final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.HealthComponentReport) */ { + public: + inline HealthComponentReport() : HealthComponentReport(nullptr) {} + ~HealthComponentReport() override; + template + explicit PROTOBUF_CONSTEXPR HealthComponentReport(::google::protobuf::internal::ConstantInitialized); + + inline HealthComponentReport(const HealthComponentReport& from) + : HealthComponentReport(nullptr, from) {} + HealthComponentReport(HealthComponentReport&& from) noexcept + : HealthComponentReport() { + *this = ::std::move(from); + } + + inline HealthComponentReport& operator=(const HealthComponentReport& from) { + CopyFrom(from); + return *this; + } + inline HealthComponentReport& operator=(HealthComponentReport&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const HealthComponentReport& default_instance() { + return *internal_default_instance(); + } + static inline const HealthComponentReport* internal_default_instance() { + return reinterpret_cast( + &_HealthComponentReport_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + friend void swap(HealthComponentReport& a, HealthComponentReport& b) { + a.Swap(&b); + } + inline void Swap(HealthComponentReport* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(HealthComponentReport* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + HealthComponentReport* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const HealthComponentReport& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const HealthComponentReport& from) { + HealthComponentReport::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(HealthComponentReport* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.HealthComponentReport"; + } + protected: + explicit HealthComponentReport(::google::protobuf::Arena* arena); + HealthComponentReport(::google::protobuf::Arena* arena, const HealthComponentReport& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kNameFieldNumber = 1, + kLabelFieldNumber = 2, + kIsPresentFieldNumber = 3, + kHasErrorFieldNumber = 4, + kHasWarningFieldNumber = 5, + }; + // string name = 1; + void clear_name() ; + const std::string& name() const; + template + void set_name(Arg_&& arg, Args_... args); + std::string* mutable_name(); + PROTOBUF_NODISCARD std::string* release_name(); + void set_allocated_name(std::string* value); + + private: + const std::string& _internal_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_name( + const std::string& value); + std::string* _internal_mutable_name(); + + public: + // string label = 2; + void clear_label() ; + const std::string& label() const; + template + void set_label(Arg_&& arg, Args_... args); + std::string* mutable_label(); + PROTOBUF_NODISCARD std::string* release_label(); + void set_allocated_label(std::string* value); + + private: + const std::string& _internal_label() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_label( + const std::string& value); + std::string* _internal_mutable_label(); + + public: + // bool is_present = 3; + void clear_is_present() ; + bool is_present() const; + void set_is_present(bool value); + + private: + bool _internal_is_present() const; + void _internal_set_is_present(bool value); + + public: + // bool has_error = 4; + void clear_has_error() ; + bool has_error() const; + void set_has_error(bool value); + + private: + bool _internal_has_error() const; + void _internal_set_has_error(bool value); + + public: + // bool has_warning = 5; + void clear_has_warning() ; + bool has_warning() const; + void set_has_warning(bool value); + + private: + bool _internal_has_warning() const; + void _internal_set_has_warning(bool value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.HealthComponentReport) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 3, 5, 0, + 57, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::ArenaStringPtr name_; + ::google::protobuf::internal::ArenaStringPtr label_; + bool is_present_; + bool has_error_; + bool has_warning_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class HealthAndArmingCheckProblem final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.HealthAndArmingCheckProblem) */ { + public: + inline HealthAndArmingCheckProblem() : HealthAndArmingCheckProblem(nullptr) {} + ~HealthAndArmingCheckProblem() override; + template + explicit PROTOBUF_CONSTEXPR HealthAndArmingCheckProblem(::google::protobuf::internal::ConstantInitialized); + + inline HealthAndArmingCheckProblem(const HealthAndArmingCheckProblem& from) + : HealthAndArmingCheckProblem(nullptr, from) {} + HealthAndArmingCheckProblem(HealthAndArmingCheckProblem&& from) noexcept + : HealthAndArmingCheckProblem() { + *this = ::std::move(from); + } + + inline HealthAndArmingCheckProblem& operator=(const HealthAndArmingCheckProblem& from) { + CopyFrom(from); + return *this; + } + inline HealthAndArmingCheckProblem& operator=(HealthAndArmingCheckProblem&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const HealthAndArmingCheckProblem& default_instance() { + return *internal_default_instance(); + } + static inline const HealthAndArmingCheckProblem* internal_default_instance() { + return reinterpret_cast( + &_HealthAndArmingCheckProblem_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + friend void swap(HealthAndArmingCheckProblem& a, HealthAndArmingCheckProblem& b) { + a.Swap(&b); + } + inline void Swap(HealthAndArmingCheckProblem* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(HealthAndArmingCheckProblem* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + HealthAndArmingCheckProblem* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const HealthAndArmingCheckProblem& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const HealthAndArmingCheckProblem& from) { + HealthAndArmingCheckProblem::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(HealthAndArmingCheckProblem* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.HealthAndArmingCheckProblem"; + } + protected: + explicit HealthAndArmingCheckProblem(::google::protobuf::Arena* arena); + HealthAndArmingCheckProblem(::google::protobuf::Arena* arena, const HealthAndArmingCheckProblem& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kMessageFieldNumber = 1, + kDescriptionFieldNumber = 2, + kHealthComponentFieldNumber = 4, + kLogLevelFieldNumber = 3, + }; + // string message = 1; + void clear_message() ; + const std::string& message() const; + template + void set_message(Arg_&& arg, Args_... args); + std::string* mutable_message(); + PROTOBUF_NODISCARD std::string* release_message(); + void set_allocated_message(std::string* value); + + private: + const std::string& _internal_message() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_message( + const std::string& value); + std::string* _internal_mutable_message(); + + public: + // string description = 2; + void clear_description() ; + const std::string& description() const; + template + void set_description(Arg_&& arg, Args_... args); + std::string* mutable_description(); + PROTOBUF_NODISCARD std::string* release_description(); + void set_allocated_description(std::string* value); + + private: + const std::string& _internal_description() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_description( + const std::string& value); + std::string* _internal_mutable_description(); + + public: + // string health_component = 4; + void clear_health_component() ; + const std::string& health_component() const; + template + void set_health_component(Arg_&& arg, Args_... args); + std::string* mutable_health_component(); + PROTOBUF_NODISCARD std::string* release_health_component(); + void set_allocated_health_component(std::string* value); + + private: + const std::string& _internal_health_component() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_health_component( + const std::string& value); + std::string* _internal_mutable_health_component(); + + public: + // .mavsdk.rpc.events.LogLevel log_level = 3; + void clear_log_level() ; + ::mavsdk::rpc::events::LogLevel log_level() const; + void set_log_level(::mavsdk::rpc::events::LogLevel value); + + private: + ::mavsdk::rpc::events::LogLevel _internal_log_level() const; + void _internal_set_log_level(::mavsdk::rpc::events::LogLevel value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.HealthAndArmingCheckProblem) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 2, 4, 0, + 88, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::ArenaStringPtr message_; + ::google::protobuf::internal::ArenaStringPtr description_; + ::google::protobuf::internal::ArenaStringPtr health_component_; + int log_level_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class GetHealthAndArmingChecksReportRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.GetHealthAndArmingChecksReportRequest) */ { + public: + inline GetHealthAndArmingChecksReportRequest() : GetHealthAndArmingChecksReportRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR GetHealthAndArmingChecksReportRequest(::google::protobuf::internal::ConstantInitialized); + + inline GetHealthAndArmingChecksReportRequest(const GetHealthAndArmingChecksReportRequest& from) + : GetHealthAndArmingChecksReportRequest(nullptr, from) {} + GetHealthAndArmingChecksReportRequest(GetHealthAndArmingChecksReportRequest&& from) noexcept + : GetHealthAndArmingChecksReportRequest() { + *this = ::std::move(from); + } + + inline GetHealthAndArmingChecksReportRequest& operator=(const GetHealthAndArmingChecksReportRequest& from) { + CopyFrom(from); + return *this; + } + inline GetHealthAndArmingChecksReportRequest& operator=(GetHealthAndArmingChecksReportRequest&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const GetHealthAndArmingChecksReportRequest& default_instance() { + return *internal_default_instance(); + } + static inline const GetHealthAndArmingChecksReportRequest* internal_default_instance() { + return reinterpret_cast( + &_GetHealthAndArmingChecksReportRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 10; + + friend void swap(GetHealthAndArmingChecksReportRequest& a, GetHealthAndArmingChecksReportRequest& b) { + a.Swap(&b); + } + inline void Swap(GetHealthAndArmingChecksReportRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(GetHealthAndArmingChecksReportRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GetHealthAndArmingChecksReportRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const GetHealthAndArmingChecksReportRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const GetHealthAndArmingChecksReportRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.GetHealthAndArmingChecksReportRequest"; + } + protected: + explicit GetHealthAndArmingChecksReportRequest(::google::protobuf::Arena* arena); + GetHealthAndArmingChecksReportRequest(::google::protobuf::Arena* arena, const GetHealthAndArmingChecksReportRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.GetHealthAndArmingChecksReportRequest) + private: + class _Internal; + + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + PROTOBUF_TSAN_DECLARE_MEMBER + }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class EventsResult final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.EventsResult) */ { + public: + inline EventsResult() : EventsResult(nullptr) {} + ~EventsResult() override; + template + explicit PROTOBUF_CONSTEXPR EventsResult(::google::protobuf::internal::ConstantInitialized); + + inline EventsResult(const EventsResult& from) + : EventsResult(nullptr, from) {} + EventsResult(EventsResult&& from) noexcept + : EventsResult() { + *this = ::std::move(from); + } + + inline EventsResult& operator=(const EventsResult& from) { + CopyFrom(from); + return *this; + } + inline EventsResult& operator=(EventsResult&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const EventsResult& default_instance() { + return *internal_default_instance(); + } + static inline const EventsResult* internal_default_instance() { + return reinterpret_cast( + &_EventsResult_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + friend void swap(EventsResult& a, EventsResult& b) { + a.Swap(&b); + } + inline void Swap(EventsResult* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(EventsResult* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + EventsResult* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const EventsResult& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const EventsResult& from) { + EventsResult::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(EventsResult* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.EventsResult"; + } + protected: + explicit EventsResult(::google::protobuf::Arena* arena); + EventsResult(::google::protobuf::Arena* arena, const EventsResult& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + using Result = EventsResult_Result; + static constexpr Result RESULT_SUCCESS = EventsResult_Result_RESULT_SUCCESS; + static constexpr Result RESULT_NOT_AVAILABLE = EventsResult_Result_RESULT_NOT_AVAILABLE; + static constexpr Result RESULT_CONNECTION_ERROR = EventsResult_Result_RESULT_CONNECTION_ERROR; + static constexpr Result RESULT_UNSUPPORTED = EventsResult_Result_RESULT_UNSUPPORTED; + static constexpr Result RESULT_DENIED = EventsResult_Result_RESULT_DENIED; + static constexpr Result RESULT_FAILED = EventsResult_Result_RESULT_FAILED; + static constexpr Result RESULT_TIMEOUT = EventsResult_Result_RESULT_TIMEOUT; + static constexpr Result RESULT_NO_SYSTEM = EventsResult_Result_RESULT_NO_SYSTEM; + static inline bool Result_IsValid(int value) { + return EventsResult_Result_IsValid(value); + } + static constexpr Result Result_MIN = EventsResult_Result_Result_MIN; + static constexpr Result Result_MAX = EventsResult_Result_Result_MAX; + static constexpr int Result_ARRAYSIZE = EventsResult_Result_Result_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* Result_descriptor() { + return EventsResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T value) { + return EventsResult_Result_Name(value); + } + static inline bool Result_Parse(absl::string_view name, Result* value) { + return EventsResult_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(Arg_&& arg, Args_... args); + std::string* mutable_result_str(); + PROTOBUF_NODISCARD std::string* release_result_str(); + void set_allocated_result_str(std::string* value); + + private: + const std::string& _internal_result_str() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_result_str( + const std::string& value); + std::string* _internal_mutable_result_str(); + + public: + // .mavsdk.rpc.events.EventsResult.Result result = 1; + void clear_result() ; + ::mavsdk::rpc::events::EventsResult_Result result() const; + void set_result(::mavsdk::rpc::events::EventsResult_Result value); + + private: + ::mavsdk::rpc::events::EventsResult_Result _internal_result() const; + void _internal_set_result(::mavsdk::rpc::events::EventsResult_Result value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.EventsResult) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 0, + 49, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::ArenaStringPtr result_str_; + int result_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class Event final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.Event) */ { + public: + inline Event() : Event(nullptr) {} + ~Event() override; + template + explicit PROTOBUF_CONSTEXPR Event(::google::protobuf::internal::ConstantInitialized); + + inline Event(const Event& from) + : Event(nullptr, from) {} + Event(Event&& from) noexcept + : Event() { + *this = ::std::move(from); + } + + inline Event& operator=(const Event& from) { + CopyFrom(from); + return *this; + } + inline Event& operator=(Event&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const Event& default_instance() { + return *internal_default_instance(); + } + static inline const Event* internal_default_instance() { + return reinterpret_cast( + &_Event_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + friend void swap(Event& a, Event& b) { + a.Swap(&b); + } + inline void Swap(Event* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Event* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Event* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const Event& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const Event& from) { + Event::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(Event* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.Event"; + } + protected: + explicit Event(::google::protobuf::Arena* arena); + Event(::google::protobuf::Arena* arena, const Event& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kMessageFieldNumber = 2, + kDescriptionFieldNumber = 3, + kEventNamespaceFieldNumber = 5, + kEventNameFieldNumber = 6, + kCompidFieldNumber = 1, + kLogLevelFieldNumber = 4, + }; + // string message = 2; + void clear_message() ; + const std::string& message() const; + template + void set_message(Arg_&& arg, Args_... args); + std::string* mutable_message(); + PROTOBUF_NODISCARD std::string* release_message(); + void set_allocated_message(std::string* value); + + private: + const std::string& _internal_message() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_message( + const std::string& value); + std::string* _internal_mutable_message(); + + public: + // string description = 3; + void clear_description() ; + const std::string& description() const; + template + void set_description(Arg_&& arg, Args_... args); + std::string* mutable_description(); + PROTOBUF_NODISCARD std::string* release_description(); + void set_allocated_description(std::string* value); + + private: + const std::string& _internal_description() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_description( + const std::string& value); + std::string* _internal_mutable_description(); + + public: + // string event_namespace = 5; + void clear_event_namespace() ; + const std::string& event_namespace() const; + template + void set_event_namespace(Arg_&& arg, Args_... args); + std::string* mutable_event_namespace(); + PROTOBUF_NODISCARD std::string* release_event_namespace(); + void set_allocated_event_namespace(std::string* value); + + private: + const std::string& _internal_event_namespace() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_event_namespace( + const std::string& value); + std::string* _internal_mutable_event_namespace(); + + public: + // string event_name = 6; + void clear_event_name() ; + const std::string& event_name() const; + template + void set_event_name(Arg_&& arg, Args_... args); + std::string* mutable_event_name(); + PROTOBUF_NODISCARD std::string* release_event_name(); + void set_allocated_event_name(std::string* value); + + private: + const std::string& _internal_event_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_event_name( + const std::string& value); + std::string* _internal_mutable_event_name(); + + public: + // uint32 compid = 1; + void clear_compid() ; + ::uint32_t compid() const; + void set_compid(::uint32_t value); + + private: + ::uint32_t _internal_compid() const; + void _internal_set_compid(::uint32_t value); + + public: + // .mavsdk.rpc.events.LogLevel log_level = 4; + void clear_log_level() ; + ::mavsdk::rpc::events::LogLevel log_level() const; + void set_log_level(::mavsdk::rpc::events::LogLevel value); + + private: + ::mavsdk::rpc::events::LogLevel _internal_log_level() const; + void _internal_set_log_level(::mavsdk::rpc::events::LogLevel value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.Event) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 3, 6, 0, + 75, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::ArenaStringPtr message_; + ::google::protobuf::internal::ArenaStringPtr description_; + ::google::protobuf::internal::ArenaStringPtr event_namespace_; + ::google::protobuf::internal::ArenaStringPtr event_name_; + ::uint32_t compid_; + int log_level_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class HealthAndArmingCheckMode final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.HealthAndArmingCheckMode) */ { + public: + inline HealthAndArmingCheckMode() : HealthAndArmingCheckMode(nullptr) {} + ~HealthAndArmingCheckMode() override; + template + explicit PROTOBUF_CONSTEXPR HealthAndArmingCheckMode(::google::protobuf::internal::ConstantInitialized); + + inline HealthAndArmingCheckMode(const HealthAndArmingCheckMode& from) + : HealthAndArmingCheckMode(nullptr, from) {} + HealthAndArmingCheckMode(HealthAndArmingCheckMode&& from) noexcept + : HealthAndArmingCheckMode() { + *this = ::std::move(from); + } + + inline HealthAndArmingCheckMode& operator=(const HealthAndArmingCheckMode& from) { + CopyFrom(from); + return *this; + } + inline HealthAndArmingCheckMode& operator=(HealthAndArmingCheckMode&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const HealthAndArmingCheckMode& default_instance() { + return *internal_default_instance(); + } + static inline const HealthAndArmingCheckMode* internal_default_instance() { + return reinterpret_cast( + &_HealthAndArmingCheckMode_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(HealthAndArmingCheckMode& a, HealthAndArmingCheckMode& b) { + a.Swap(&b); + } + inline void Swap(HealthAndArmingCheckMode* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(HealthAndArmingCheckMode* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + HealthAndArmingCheckMode* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const HealthAndArmingCheckMode& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const HealthAndArmingCheckMode& from) { + HealthAndArmingCheckMode::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(HealthAndArmingCheckMode* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.HealthAndArmingCheckMode"; + } + protected: + explicit HealthAndArmingCheckMode(::google::protobuf::Arena* arena); + HealthAndArmingCheckMode(::google::protobuf::Arena* arena, const HealthAndArmingCheckMode& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kProblemsFieldNumber = 3, + kModeNameFieldNumber = 1, + kCanArmOrRunFieldNumber = 2, + }; + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem problems = 3; + int problems_size() const; + private: + int _internal_problems_size() const; + + public: + void clear_problems() ; + ::mavsdk::rpc::events::HealthAndArmingCheckProblem* mutable_problems(int index); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthAndArmingCheckProblem >* + mutable_problems(); + private: + const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>& _internal_problems() const; + ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>* _internal_mutable_problems(); + public: + const ::mavsdk::rpc::events::HealthAndArmingCheckProblem& problems(int index) const; + ::mavsdk::rpc::events::HealthAndArmingCheckProblem* add_problems(); + const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthAndArmingCheckProblem >& + problems() const; + // string mode_name = 1; + void clear_mode_name() ; + const std::string& mode_name() const; + template + void set_mode_name(Arg_&& arg, Args_... args); + std::string* mutable_mode_name(); + PROTOBUF_NODISCARD std::string* release_mode_name(); + void set_allocated_mode_name(std::string* value); + + private: + const std::string& _internal_mode_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_mode_name( + const std::string& value); + std::string* _internal_mutable_mode_name(); + + public: + // bool can_arm_or_run = 2; + void clear_can_arm_or_run() ; + bool can_arm_or_run() const; + void set_can_arm_or_run(bool value); + + private: + bool _internal_can_arm_or_run() const; + void _internal_set_can_arm_or_run(bool value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.HealthAndArmingCheckMode) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 2, 3, 1, + 60, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthAndArmingCheckProblem > problems_; + ::google::protobuf::internal::ArenaStringPtr mode_name_; + bool can_arm_or_run_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class EventsResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.EventsResponse) */ { + public: + inline EventsResponse() : EventsResponse(nullptr) {} + ~EventsResponse() override; + template + explicit PROTOBUF_CONSTEXPR EventsResponse(::google::protobuf::internal::ConstantInitialized); + + inline EventsResponse(const EventsResponse& from) + : EventsResponse(nullptr, from) {} + EventsResponse(EventsResponse&& from) noexcept + : EventsResponse() { + *this = ::std::move(from); + } + + inline EventsResponse& operator=(const EventsResponse& from) { + CopyFrom(from); + return *this; + } + inline EventsResponse& operator=(EventsResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const EventsResponse& default_instance() { + return *internal_default_instance(); + } + static inline const EventsResponse* internal_default_instance() { + return reinterpret_cast( + &_EventsResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 7; + + friend void swap(EventsResponse& a, EventsResponse& b) { + a.Swap(&b); + } + inline void Swap(EventsResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(EventsResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + EventsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const EventsResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const EventsResponse& from) { + EventsResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(EventsResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.EventsResponse"; + } + protected: + explicit EventsResponse(::google::protobuf::Arena* arena); + EventsResponse(::google::protobuf::Arena* arena, const EventsResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kEventFieldNumber = 1, + }; + // .mavsdk.rpc.events.Event event = 1; + bool has_event() const; + void clear_event() ; + const ::mavsdk::rpc::events::Event& event() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::events::Event* release_event(); + ::mavsdk::rpc::events::Event* mutable_event(); + void set_allocated_event(::mavsdk::rpc::events::Event* value); + void unsafe_arena_set_allocated_event(::mavsdk::rpc::events::Event* value); + ::mavsdk::rpc::events::Event* unsafe_arena_release_event(); + + private: + const ::mavsdk::rpc::events::Event& _internal_event() const; + ::mavsdk::rpc::events::Event* _internal_mutable_event(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.EventsResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::events::Event* event_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class HealthAndArmingCheckReport final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.HealthAndArmingCheckReport) */ { + public: + inline HealthAndArmingCheckReport() : HealthAndArmingCheckReport(nullptr) {} + ~HealthAndArmingCheckReport() override; + template + explicit PROTOBUF_CONSTEXPR HealthAndArmingCheckReport(::google::protobuf::internal::ConstantInitialized); + + inline HealthAndArmingCheckReport(const HealthAndArmingCheckReport& from) + : HealthAndArmingCheckReport(nullptr, from) {} + HealthAndArmingCheckReport(HealthAndArmingCheckReport&& from) noexcept + : HealthAndArmingCheckReport() { + *this = ::std::move(from); + } + + inline HealthAndArmingCheckReport& operator=(const HealthAndArmingCheckReport& from) { + CopyFrom(from); + return *this; + } + inline HealthAndArmingCheckReport& operator=(HealthAndArmingCheckReport&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const HealthAndArmingCheckReport& default_instance() { + return *internal_default_instance(); + } + static inline const HealthAndArmingCheckReport* internal_default_instance() { + return reinterpret_cast( + &_HealthAndArmingCheckReport_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + friend void swap(HealthAndArmingCheckReport& a, HealthAndArmingCheckReport& b) { + a.Swap(&b); + } + inline void Swap(HealthAndArmingCheckReport* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(HealthAndArmingCheckReport* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + HealthAndArmingCheckReport* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const HealthAndArmingCheckReport& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const HealthAndArmingCheckReport& from) { + HealthAndArmingCheckReport::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(HealthAndArmingCheckReport* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.HealthAndArmingCheckReport"; + } + protected: + explicit HealthAndArmingCheckReport(::google::protobuf::Arena* arena); + HealthAndArmingCheckReport(::google::protobuf::Arena* arena, const HealthAndArmingCheckReport& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kHealthComponentsFieldNumber = 2, + kAllProblemsFieldNumber = 3, + kCurrentModeIntentionFieldNumber = 1, + }; + // repeated .mavsdk.rpc.events.HealthComponentReport health_components = 2; + int health_components_size() const; + private: + int _internal_health_components_size() const; + + public: + void clear_health_components() ; + ::mavsdk::rpc::events::HealthComponentReport* mutable_health_components(int index); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthComponentReport >* + mutable_health_components(); + private: + const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthComponentReport>& _internal_health_components() const; + ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthComponentReport>* _internal_mutable_health_components(); + public: + const ::mavsdk::rpc::events::HealthComponentReport& health_components(int index) const; + ::mavsdk::rpc::events::HealthComponentReport* add_health_components(); + const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthComponentReport >& + health_components() const; + // repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem all_problems = 3; + int all_problems_size() const; + private: + int _internal_all_problems_size() const; + + public: + void clear_all_problems() ; + ::mavsdk::rpc::events::HealthAndArmingCheckProblem* mutable_all_problems(int index); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthAndArmingCheckProblem >* + mutable_all_problems(); + private: + const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>& _internal_all_problems() const; + ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>* _internal_mutable_all_problems(); + public: + const ::mavsdk::rpc::events::HealthAndArmingCheckProblem& all_problems(int index) const; + ::mavsdk::rpc::events::HealthAndArmingCheckProblem* add_all_problems(); + const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthAndArmingCheckProblem >& + all_problems() const; + // .mavsdk.rpc.events.HealthAndArmingCheckMode current_mode_intention = 1; + bool has_current_mode_intention() const; + void clear_current_mode_intention() ; + const ::mavsdk::rpc::events::HealthAndArmingCheckMode& current_mode_intention() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::events::HealthAndArmingCheckMode* release_current_mode_intention(); + ::mavsdk::rpc::events::HealthAndArmingCheckMode* mutable_current_mode_intention(); + void set_allocated_current_mode_intention(::mavsdk::rpc::events::HealthAndArmingCheckMode* value); + void unsafe_arena_set_allocated_current_mode_intention(::mavsdk::rpc::events::HealthAndArmingCheckMode* value); + ::mavsdk::rpc::events::HealthAndArmingCheckMode* unsafe_arena_release_current_mode_intention(); + + private: + const ::mavsdk::rpc::events::HealthAndArmingCheckMode& _internal_current_mode_intention() const; + ::mavsdk::rpc::events::HealthAndArmingCheckMode* _internal_mutable_current_mode_intention(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.HealthAndArmingCheckReport) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 2, 3, 3, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthComponentReport > health_components_; + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::events::HealthAndArmingCheckProblem > all_problems_; + ::mavsdk::rpc::events::HealthAndArmingCheckMode* current_mode_intention_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class HealthAndArmingChecksResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.HealthAndArmingChecksResponse) */ { + public: + inline HealthAndArmingChecksResponse() : HealthAndArmingChecksResponse(nullptr) {} + ~HealthAndArmingChecksResponse() override; + template + explicit PROTOBUF_CONSTEXPR HealthAndArmingChecksResponse(::google::protobuf::internal::ConstantInitialized); + + inline HealthAndArmingChecksResponse(const HealthAndArmingChecksResponse& from) + : HealthAndArmingChecksResponse(nullptr, from) {} + HealthAndArmingChecksResponse(HealthAndArmingChecksResponse&& from) noexcept + : HealthAndArmingChecksResponse() { + *this = ::std::move(from); + } + + inline HealthAndArmingChecksResponse& operator=(const HealthAndArmingChecksResponse& from) { + CopyFrom(from); + return *this; + } + inline HealthAndArmingChecksResponse& operator=(HealthAndArmingChecksResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const HealthAndArmingChecksResponse& default_instance() { + return *internal_default_instance(); + } + static inline const HealthAndArmingChecksResponse* internal_default_instance() { + return reinterpret_cast( + &_HealthAndArmingChecksResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 9; + + friend void swap(HealthAndArmingChecksResponse& a, HealthAndArmingChecksResponse& b) { + a.Swap(&b); + } + inline void Swap(HealthAndArmingChecksResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(HealthAndArmingChecksResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + HealthAndArmingChecksResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const HealthAndArmingChecksResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const HealthAndArmingChecksResponse& from) { + HealthAndArmingChecksResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(HealthAndArmingChecksResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.HealthAndArmingChecksResponse"; + } + protected: + explicit HealthAndArmingChecksResponse(::google::protobuf::Arena* arena); + HealthAndArmingChecksResponse(::google::protobuf::Arena* arena, const HealthAndArmingChecksResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kReportFieldNumber = 1, + }; + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 1; + bool has_report() const; + void clear_report() ; + const ::mavsdk::rpc::events::HealthAndArmingCheckReport& report() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::events::HealthAndArmingCheckReport* release_report(); + ::mavsdk::rpc::events::HealthAndArmingCheckReport* mutable_report(); + void set_allocated_report(::mavsdk::rpc::events::HealthAndArmingCheckReport* value); + void unsafe_arena_set_allocated_report(::mavsdk::rpc::events::HealthAndArmingCheckReport* value); + ::mavsdk::rpc::events::HealthAndArmingCheckReport* unsafe_arena_release_report(); + + private: + const ::mavsdk::rpc::events::HealthAndArmingCheckReport& _internal_report() const; + ::mavsdk::rpc::events::HealthAndArmingCheckReport* _internal_mutable_report(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.HealthAndArmingChecksResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::events::HealthAndArmingCheckReport* report_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +};// ------------------------------------------------------------------- + +class GetHealthAndArmingChecksReportResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) */ { + public: + inline GetHealthAndArmingChecksReportResponse() : GetHealthAndArmingChecksReportResponse(nullptr) {} + ~GetHealthAndArmingChecksReportResponse() override; + template + explicit PROTOBUF_CONSTEXPR GetHealthAndArmingChecksReportResponse(::google::protobuf::internal::ConstantInitialized); + + inline GetHealthAndArmingChecksReportResponse(const GetHealthAndArmingChecksReportResponse& from) + : GetHealthAndArmingChecksReportResponse(nullptr, from) {} + GetHealthAndArmingChecksReportResponse(GetHealthAndArmingChecksReportResponse&& from) noexcept + : GetHealthAndArmingChecksReportResponse() { + *this = ::std::move(from); + } + + inline GetHealthAndArmingChecksReportResponse& operator=(const GetHealthAndArmingChecksReportResponse& from) { + CopyFrom(from); + return *this; + } + inline GetHealthAndArmingChecksReportResponse& operator=(GetHealthAndArmingChecksReportResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const GetHealthAndArmingChecksReportResponse& default_instance() { + return *internal_default_instance(); + } + static inline const GetHealthAndArmingChecksReportResponse* internal_default_instance() { + return reinterpret_cast( + &_GetHealthAndArmingChecksReportResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 11; + + friend void swap(GetHealthAndArmingChecksReportResponse& a, GetHealthAndArmingChecksReportResponse& b) { + a.Swap(&b); + } + inline void Swap(GetHealthAndArmingChecksReportResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(GetHealthAndArmingChecksReportResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GetHealthAndArmingChecksReportResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const GetHealthAndArmingChecksReportResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const GetHealthAndArmingChecksReportResponse& from) { + GetHealthAndArmingChecksReportResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(GetHealthAndArmingChecksReportResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse"; + } + protected: + explicit GetHealthAndArmingChecksReportResponse(::google::protobuf::Arena* arena); + GetHealthAndArmingChecksReportResponse(::google::protobuf::Arena* arena, const GetHealthAndArmingChecksReportResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kEventsResultFieldNumber = 1, + kReportFieldNumber = 2, + }; + // .mavsdk.rpc.events.EventsResult events_result = 1; + bool has_events_result() const; + void clear_events_result() ; + const ::mavsdk::rpc::events::EventsResult& events_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::events::EventsResult* release_events_result(); + ::mavsdk::rpc::events::EventsResult* mutable_events_result(); + void set_allocated_events_result(::mavsdk::rpc::events::EventsResult* value); + void unsafe_arena_set_allocated_events_result(::mavsdk::rpc::events::EventsResult* value); + ::mavsdk::rpc::events::EventsResult* unsafe_arena_release_events_result(); + + private: + const ::mavsdk::rpc::events::EventsResult& _internal_events_result() const; + ::mavsdk::rpc::events::EventsResult* _internal_mutable_events_result(); + + public: + // .mavsdk.rpc.events.HealthAndArmingCheckReport report = 2; + bool has_report() const; + void clear_report() ; + const ::mavsdk::rpc::events::HealthAndArmingCheckReport& report() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::events::HealthAndArmingCheckReport* release_report(); + ::mavsdk::rpc::events::HealthAndArmingCheckReport* mutable_report(); + void set_allocated_report(::mavsdk::rpc::events::HealthAndArmingCheckReport* value); + void unsafe_arena_set_allocated_report(::mavsdk::rpc::events::HealthAndArmingCheckReport* value); + ::mavsdk::rpc::events::HealthAndArmingCheckReport* unsafe_arena_release_report(); + + private: + const ::mavsdk::rpc::events::HealthAndArmingCheckReport& _internal_report() const; + ::mavsdk::rpc::events::HealthAndArmingCheckReport* _internal_mutable_report(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 2, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::events::EventsResult* events_result_; + ::mavsdk::rpc::events::HealthAndArmingCheckReport* report_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_events_2fevents_2eproto; +}; + +// =================================================================== + + + + +// =================================================================== + + +#ifdef __GNUC__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// Event + +// uint32 compid = 1; +inline void Event::clear_compid() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.compid_ = 0u; +} +inline ::uint32_t Event::compid() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.Event.compid) + return _internal_compid(); +} +inline void Event::set_compid(::uint32_t value) { + _internal_set_compid(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.Event.compid) +} +inline ::uint32_t Event::_internal_compid() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.compid_; +} +inline void Event::_internal_set_compid(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.compid_ = value; +} + +// string message = 2; +inline void Event::clear_message() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.message_.ClearToEmpty(); +} +inline const std::string& Event::message() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.Event.message) + return _internal_message(); +} +template +inline PROTOBUF_ALWAYS_INLINE void Event::set_message(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.message_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.Event.message) +} +inline std::string* Event::mutable_message() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_message(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.Event.message) + return _s; +} +inline const std::string& Event::_internal_message() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.message_.Get(); +} +inline void Event::_internal_set_message(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.message_.Set(value, GetArena()); +} +inline std::string* Event::_internal_mutable_message() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.message_.Mutable( GetArena()); +} +inline std::string* Event::release_message() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.Event.message) + return _impl_.message_.Release(); +} +inline void Event::set_allocated_message(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.message_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.message_.IsDefault()) { + _impl_.message_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.Event.message) +} + +// string description = 3; +inline void Event::clear_description() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.description_.ClearToEmpty(); +} +inline const std::string& Event::description() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.Event.description) + return _internal_description(); +} +template +inline PROTOBUF_ALWAYS_INLINE void Event::set_description(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.description_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.Event.description) +} +inline std::string* Event::mutable_description() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_description(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.Event.description) + return _s; +} +inline const std::string& Event::_internal_description() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.description_.Get(); +} +inline void Event::_internal_set_description(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.description_.Set(value, GetArena()); +} +inline std::string* Event::_internal_mutable_description() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.description_.Mutable( GetArena()); +} +inline std::string* Event::release_description() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.Event.description) + return _impl_.description_.Release(); +} +inline void Event::set_allocated_description(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.description_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.description_.IsDefault()) { + _impl_.description_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.Event.description) +} + +// .mavsdk.rpc.events.LogLevel log_level = 4; +inline void Event::clear_log_level() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.log_level_ = 0; +} +inline ::mavsdk::rpc::events::LogLevel Event::log_level() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.Event.log_level) + return _internal_log_level(); +} +inline void Event::set_log_level(::mavsdk::rpc::events::LogLevel value) { + _internal_set_log_level(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.Event.log_level) +} +inline ::mavsdk::rpc::events::LogLevel Event::_internal_log_level() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::events::LogLevel>(_impl_.log_level_); +} +inline void Event::_internal_set_log_level(::mavsdk::rpc::events::LogLevel value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.log_level_ = value; +} + +// string event_namespace = 5; +inline void Event::clear_event_namespace() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.event_namespace_.ClearToEmpty(); +} +inline const std::string& Event::event_namespace() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.Event.event_namespace) + return _internal_event_namespace(); +} +template +inline PROTOBUF_ALWAYS_INLINE void Event::set_event_namespace(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.event_namespace_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.Event.event_namespace) +} +inline std::string* Event::mutable_event_namespace() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_event_namespace(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.Event.event_namespace) + return _s; +} +inline const std::string& Event::_internal_event_namespace() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.event_namespace_.Get(); +} +inline void Event::_internal_set_event_namespace(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.event_namespace_.Set(value, GetArena()); +} +inline std::string* Event::_internal_mutable_event_namespace() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.event_namespace_.Mutable( GetArena()); +} +inline std::string* Event::release_event_namespace() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.Event.event_namespace) + return _impl_.event_namespace_.Release(); +} +inline void Event::set_allocated_event_namespace(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.event_namespace_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.event_namespace_.IsDefault()) { + _impl_.event_namespace_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.Event.event_namespace) +} + +// string event_name = 6; +inline void Event::clear_event_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.event_name_.ClearToEmpty(); +} +inline const std::string& Event::event_name() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.Event.event_name) + return _internal_event_name(); +} +template +inline PROTOBUF_ALWAYS_INLINE void Event::set_event_name(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.event_name_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.Event.event_name) +} +inline std::string* Event::mutable_event_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_event_name(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.Event.event_name) + return _s; +} +inline const std::string& Event::_internal_event_name() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.event_name_.Get(); +} +inline void Event::_internal_set_event_name(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.event_name_.Set(value, GetArena()); +} +inline std::string* Event::_internal_mutable_event_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.event_name_.Mutable( GetArena()); +} +inline std::string* Event::release_event_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.Event.event_name) + return _impl_.event_name_.Release(); +} +inline void Event::set_allocated_event_name(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.event_name_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.event_name_.IsDefault()) { + _impl_.event_name_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.Event.event_name) +} + +// ------------------------------------------------------------------- + +// HealthAndArmingCheckProblem + +// string message = 1; +inline void HealthAndArmingCheckProblem::clear_message() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.message_.ClearToEmpty(); +} +inline const std::string& HealthAndArmingCheckProblem::message() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckProblem.message) + return _internal_message(); +} +template +inline PROTOBUF_ALWAYS_INLINE void HealthAndArmingCheckProblem::set_message(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.message_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthAndArmingCheckProblem.message) +} +inline std::string* HealthAndArmingCheckProblem::mutable_message() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_message(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingCheckProblem.message) + return _s; +} +inline const std::string& HealthAndArmingCheckProblem::_internal_message() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.message_.Get(); +} +inline void HealthAndArmingCheckProblem::_internal_set_message(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.message_.Set(value, GetArena()); +} +inline std::string* HealthAndArmingCheckProblem::_internal_mutable_message() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.message_.Mutable( GetArena()); +} +inline std::string* HealthAndArmingCheckProblem::release_message() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.HealthAndArmingCheckProblem.message) + return _impl_.message_.Release(); +} +inline void HealthAndArmingCheckProblem::set_allocated_message(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.message_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.message_.IsDefault()) { + _impl_.message_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.HealthAndArmingCheckProblem.message) +} + +// string description = 2; +inline void HealthAndArmingCheckProblem::clear_description() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.description_.ClearToEmpty(); +} +inline const std::string& HealthAndArmingCheckProblem::description() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckProblem.description) + return _internal_description(); +} +template +inline PROTOBUF_ALWAYS_INLINE void HealthAndArmingCheckProblem::set_description(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.description_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthAndArmingCheckProblem.description) +} +inline std::string* HealthAndArmingCheckProblem::mutable_description() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_description(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingCheckProblem.description) + return _s; +} +inline const std::string& HealthAndArmingCheckProblem::_internal_description() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.description_.Get(); +} +inline void HealthAndArmingCheckProblem::_internal_set_description(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.description_.Set(value, GetArena()); +} +inline std::string* HealthAndArmingCheckProblem::_internal_mutable_description() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.description_.Mutable( GetArena()); +} +inline std::string* HealthAndArmingCheckProblem::release_description() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.HealthAndArmingCheckProblem.description) + return _impl_.description_.Release(); +} +inline void HealthAndArmingCheckProblem::set_allocated_description(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.description_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.description_.IsDefault()) { + _impl_.description_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.HealthAndArmingCheckProblem.description) +} + +// .mavsdk.rpc.events.LogLevel log_level = 3; +inline void HealthAndArmingCheckProblem::clear_log_level() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.log_level_ = 0; +} +inline ::mavsdk::rpc::events::LogLevel HealthAndArmingCheckProblem::log_level() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckProblem.log_level) + return _internal_log_level(); +} +inline void HealthAndArmingCheckProblem::set_log_level(::mavsdk::rpc::events::LogLevel value) { + _internal_set_log_level(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthAndArmingCheckProblem.log_level) +} +inline ::mavsdk::rpc::events::LogLevel HealthAndArmingCheckProblem::_internal_log_level() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::events::LogLevel>(_impl_.log_level_); +} +inline void HealthAndArmingCheckProblem::_internal_set_log_level(::mavsdk::rpc::events::LogLevel value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.log_level_ = value; +} + +// string health_component = 4; +inline void HealthAndArmingCheckProblem::clear_health_component() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.health_component_.ClearToEmpty(); +} +inline const std::string& HealthAndArmingCheckProblem::health_component() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckProblem.health_component) + return _internal_health_component(); +} +template +inline PROTOBUF_ALWAYS_INLINE void HealthAndArmingCheckProblem::set_health_component(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.health_component_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthAndArmingCheckProblem.health_component) +} +inline std::string* HealthAndArmingCheckProblem::mutable_health_component() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_health_component(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingCheckProblem.health_component) + return _s; +} +inline const std::string& HealthAndArmingCheckProblem::_internal_health_component() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.health_component_.Get(); +} +inline void HealthAndArmingCheckProblem::_internal_set_health_component(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.health_component_.Set(value, GetArena()); +} +inline std::string* HealthAndArmingCheckProblem::_internal_mutable_health_component() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.health_component_.Mutable( GetArena()); +} +inline std::string* HealthAndArmingCheckProblem::release_health_component() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.HealthAndArmingCheckProblem.health_component) + return _impl_.health_component_.Release(); +} +inline void HealthAndArmingCheckProblem::set_allocated_health_component(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.health_component_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.health_component_.IsDefault()) { + _impl_.health_component_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.HealthAndArmingCheckProblem.health_component) +} + +// ------------------------------------------------------------------- + +// HealthAndArmingCheckMode + +// string mode_name = 1; +inline void HealthAndArmingCheckMode::clear_mode_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.mode_name_.ClearToEmpty(); +} +inline const std::string& HealthAndArmingCheckMode::mode_name() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckMode.mode_name) + return _internal_mode_name(); +} +template +inline PROTOBUF_ALWAYS_INLINE void HealthAndArmingCheckMode::set_mode_name(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.mode_name_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthAndArmingCheckMode.mode_name) +} +inline std::string* HealthAndArmingCheckMode::mutable_mode_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_mode_name(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingCheckMode.mode_name) + return _s; +} +inline const std::string& HealthAndArmingCheckMode::_internal_mode_name() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.mode_name_.Get(); +} +inline void HealthAndArmingCheckMode::_internal_set_mode_name(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.mode_name_.Set(value, GetArena()); +} +inline std::string* HealthAndArmingCheckMode::_internal_mutable_mode_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.mode_name_.Mutable( GetArena()); +} +inline std::string* HealthAndArmingCheckMode::release_mode_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.HealthAndArmingCheckMode.mode_name) + return _impl_.mode_name_.Release(); +} +inline void HealthAndArmingCheckMode::set_allocated_mode_name(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.mode_name_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.mode_name_.IsDefault()) { + _impl_.mode_name_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.HealthAndArmingCheckMode.mode_name) +} + +// bool can_arm_or_run = 2; +inline void HealthAndArmingCheckMode::clear_can_arm_or_run() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.can_arm_or_run_ = false; +} +inline bool HealthAndArmingCheckMode::can_arm_or_run() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckMode.can_arm_or_run) + return _internal_can_arm_or_run(); +} +inline void HealthAndArmingCheckMode::set_can_arm_or_run(bool value) { + _internal_set_can_arm_or_run(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthAndArmingCheckMode.can_arm_or_run) +} +inline bool HealthAndArmingCheckMode::_internal_can_arm_or_run() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.can_arm_or_run_; +} +inline void HealthAndArmingCheckMode::_internal_set_can_arm_or_run(bool value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.can_arm_or_run_ = value; +} + +// repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem problems = 3; +inline int HealthAndArmingCheckMode::_internal_problems_size() const { + return _internal_problems().size(); +} +inline int HealthAndArmingCheckMode::problems_size() const { + return _internal_problems_size(); +} +inline void HealthAndArmingCheckMode::clear_problems() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.problems_.Clear(); +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckProblem* HealthAndArmingCheckMode::mutable_problems(int index) + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingCheckMode.problems) + return _internal_mutable_problems()->Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>* HealthAndArmingCheckMode::mutable_problems() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.events.HealthAndArmingCheckMode.problems) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_problems(); +} +inline const ::mavsdk::rpc::events::HealthAndArmingCheckProblem& HealthAndArmingCheckMode::problems(int index) const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckMode.problems) + return _internal_problems().Get(index); +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckProblem* HealthAndArmingCheckMode::add_problems() ABSL_ATTRIBUTE_LIFETIME_BOUND { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::mavsdk::rpc::events::HealthAndArmingCheckProblem* _add = _internal_mutable_problems()->Add(); + // @@protoc_insertion_point(field_add:mavsdk.rpc.events.HealthAndArmingCheckMode.problems) + return _add; +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>& HealthAndArmingCheckMode::problems() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.events.HealthAndArmingCheckMode.problems) + return _internal_problems(); +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>& +HealthAndArmingCheckMode::_internal_problems() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.problems_; +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>* +HealthAndArmingCheckMode::_internal_mutable_problems() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.problems_; +} + +// ------------------------------------------------------------------- + +// HealthComponentReport + +// string name = 1; +inline void HealthComponentReport::clear_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.name_.ClearToEmpty(); +} +inline const std::string& HealthComponentReport::name() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthComponentReport.name) + return _internal_name(); +} +template +inline PROTOBUF_ALWAYS_INLINE void HealthComponentReport::set_name(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.name_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthComponentReport.name) +} +inline std::string* HealthComponentReport::mutable_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_name(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthComponentReport.name) + return _s; +} +inline const std::string& HealthComponentReport::_internal_name() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.name_.Get(); +} +inline void HealthComponentReport::_internal_set_name(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.name_.Set(value, GetArena()); +} +inline std::string* HealthComponentReport::_internal_mutable_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.name_.Mutable( GetArena()); +} +inline std::string* HealthComponentReport::release_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.HealthComponentReport.name) + return _impl_.name_.Release(); +} +inline void HealthComponentReport::set_allocated_name(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.name_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.name_.IsDefault()) { + _impl_.name_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.HealthComponentReport.name) +} + +// string label = 2; +inline void HealthComponentReport::clear_label() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.label_.ClearToEmpty(); +} +inline const std::string& HealthComponentReport::label() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthComponentReport.label) + return _internal_label(); +} +template +inline PROTOBUF_ALWAYS_INLINE void HealthComponentReport::set_label(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.label_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthComponentReport.label) +} +inline std::string* HealthComponentReport::mutable_label() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_label(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthComponentReport.label) + return _s; +} +inline const std::string& HealthComponentReport::_internal_label() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.label_.Get(); +} +inline void HealthComponentReport::_internal_set_label(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.label_.Set(value, GetArena()); +} +inline std::string* HealthComponentReport::_internal_mutable_label() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.label_.Mutable( GetArena()); +} +inline std::string* HealthComponentReport::release_label() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.HealthComponentReport.label) + return _impl_.label_.Release(); +} +inline void HealthComponentReport::set_allocated_label(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.label_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.label_.IsDefault()) { + _impl_.label_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.HealthComponentReport.label) +} + +// bool is_present = 3; +inline void HealthComponentReport::clear_is_present() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.is_present_ = false; +} +inline bool HealthComponentReport::is_present() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthComponentReport.is_present) + return _internal_is_present(); +} +inline void HealthComponentReport::set_is_present(bool value) { + _internal_set_is_present(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthComponentReport.is_present) +} +inline bool HealthComponentReport::_internal_is_present() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.is_present_; +} +inline void HealthComponentReport::_internal_set_is_present(bool value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.is_present_ = value; +} + +// bool has_error = 4; +inline void HealthComponentReport::clear_has_error() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.has_error_ = false; +} +inline bool HealthComponentReport::has_error() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthComponentReport.has_error) + return _internal_has_error(); +} +inline void HealthComponentReport::set_has_error(bool value) { + _internal_set_has_error(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthComponentReport.has_error) +} +inline bool HealthComponentReport::_internal_has_error() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.has_error_; +} +inline void HealthComponentReport::_internal_set_has_error(bool value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.has_error_ = value; +} + +// bool has_warning = 5; +inline void HealthComponentReport::clear_has_warning() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.has_warning_ = false; +} +inline bool HealthComponentReport::has_warning() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthComponentReport.has_warning) + return _internal_has_warning(); +} +inline void HealthComponentReport::set_has_warning(bool value) { + _internal_set_has_warning(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.HealthComponentReport.has_warning) +} +inline bool HealthComponentReport::_internal_has_warning() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.has_warning_; +} +inline void HealthComponentReport::_internal_set_has_warning(bool value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.has_warning_ = value; +} + +// ------------------------------------------------------------------- + +// HealthAndArmingCheckReport + +// .mavsdk.rpc.events.HealthAndArmingCheckMode current_mode_intention = 1; +inline bool HealthAndArmingCheckReport::has_current_mode_intention() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.current_mode_intention_ != nullptr); + return value; +} +inline void HealthAndArmingCheckReport::clear_current_mode_intention() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.current_mode_intention_ != nullptr) _impl_.current_mode_intention_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::events::HealthAndArmingCheckMode& HealthAndArmingCheckReport::_internal_current_mode_intention() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::events::HealthAndArmingCheckMode* p = _impl_.current_mode_intention_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::events::_HealthAndArmingCheckMode_default_instance_); +} +inline const ::mavsdk::rpc::events::HealthAndArmingCheckMode& HealthAndArmingCheckReport::current_mode_intention() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckReport.current_mode_intention) + return _internal_current_mode_intention(); +} +inline void HealthAndArmingCheckReport::unsafe_arena_set_allocated_current_mode_intention(::mavsdk::rpc::events::HealthAndArmingCheckMode* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.current_mode_intention_); + } + _impl_.current_mode_intention_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckMode*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.events.HealthAndArmingCheckReport.current_mode_intention) +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckMode* HealthAndArmingCheckReport::release_current_mode_intention() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::events::HealthAndArmingCheckMode* released = _impl_.current_mode_intention_; + _impl_.current_mode_intention_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckMode* HealthAndArmingCheckReport::unsafe_arena_release_current_mode_intention() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.HealthAndArmingCheckReport.current_mode_intention) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::events::HealthAndArmingCheckMode* temp = _impl_.current_mode_intention_; + _impl_.current_mode_intention_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckMode* HealthAndArmingCheckReport::_internal_mutable_current_mode_intention() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.current_mode_intention_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::events::HealthAndArmingCheckMode>(GetArena()); + _impl_.current_mode_intention_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckMode*>(p); + } + return _impl_.current_mode_intention_; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckMode* HealthAndArmingCheckReport::mutable_current_mode_intention() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::events::HealthAndArmingCheckMode* _msg = _internal_mutable_current_mode_intention(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingCheckReport.current_mode_intention) + return _msg; +} +inline void HealthAndArmingCheckReport::set_allocated_current_mode_intention(::mavsdk::rpc::events::HealthAndArmingCheckMode* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckMode*>(_impl_.current_mode_intention_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckMode*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.current_mode_intention_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckMode*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.HealthAndArmingCheckReport.current_mode_intention) +} + +// repeated .mavsdk.rpc.events.HealthComponentReport health_components = 2; +inline int HealthAndArmingCheckReport::_internal_health_components_size() const { + return _internal_health_components().size(); +} +inline int HealthAndArmingCheckReport::health_components_size() const { + return _internal_health_components_size(); +} +inline void HealthAndArmingCheckReport::clear_health_components() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.health_components_.Clear(); +} +inline ::mavsdk::rpc::events::HealthComponentReport* HealthAndArmingCheckReport::mutable_health_components(int index) + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingCheckReport.health_components) + return _internal_mutable_health_components()->Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthComponentReport>* HealthAndArmingCheckReport::mutable_health_components() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.events.HealthAndArmingCheckReport.health_components) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_health_components(); +} +inline const ::mavsdk::rpc::events::HealthComponentReport& HealthAndArmingCheckReport::health_components(int index) const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckReport.health_components) + return _internal_health_components().Get(index); +} +inline ::mavsdk::rpc::events::HealthComponentReport* HealthAndArmingCheckReport::add_health_components() ABSL_ATTRIBUTE_LIFETIME_BOUND { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::mavsdk::rpc::events::HealthComponentReport* _add = _internal_mutable_health_components()->Add(); + // @@protoc_insertion_point(field_add:mavsdk.rpc.events.HealthAndArmingCheckReport.health_components) + return _add; +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthComponentReport>& HealthAndArmingCheckReport::health_components() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.events.HealthAndArmingCheckReport.health_components) + return _internal_health_components(); +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthComponentReport>& +HealthAndArmingCheckReport::_internal_health_components() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.health_components_; +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthComponentReport>* +HealthAndArmingCheckReport::_internal_mutable_health_components() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.health_components_; +} + +// repeated .mavsdk.rpc.events.HealthAndArmingCheckProblem all_problems = 3; +inline int HealthAndArmingCheckReport::_internal_all_problems_size() const { + return _internal_all_problems().size(); +} +inline int HealthAndArmingCheckReport::all_problems_size() const { + return _internal_all_problems_size(); +} +inline void HealthAndArmingCheckReport::clear_all_problems() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.all_problems_.Clear(); +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckProblem* HealthAndArmingCheckReport::mutable_all_problems(int index) + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingCheckReport.all_problems) + return _internal_mutable_all_problems()->Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>* HealthAndArmingCheckReport::mutable_all_problems() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.events.HealthAndArmingCheckReport.all_problems) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_all_problems(); +} +inline const ::mavsdk::rpc::events::HealthAndArmingCheckProblem& HealthAndArmingCheckReport::all_problems(int index) const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingCheckReport.all_problems) + return _internal_all_problems().Get(index); +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckProblem* HealthAndArmingCheckReport::add_all_problems() ABSL_ATTRIBUTE_LIFETIME_BOUND { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::mavsdk::rpc::events::HealthAndArmingCheckProblem* _add = _internal_mutable_all_problems()->Add(); + // @@protoc_insertion_point(field_add:mavsdk.rpc.events.HealthAndArmingCheckReport.all_problems) + return _add; +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>& HealthAndArmingCheckReport::all_problems() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.events.HealthAndArmingCheckReport.all_problems) + return _internal_all_problems(); +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>& +HealthAndArmingCheckReport::_internal_all_problems() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.all_problems_; +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::events::HealthAndArmingCheckProblem>* +HealthAndArmingCheckReport::_internal_mutable_all_problems() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.all_problems_; +} + +// ------------------------------------------------------------------- + +// EventsResult + +// .mavsdk.rpc.events.EventsResult.Result result = 1; +inline void EventsResult::clear_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.result_ = 0; +} +inline ::mavsdk::rpc::events::EventsResult_Result EventsResult::result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.EventsResult.result) + return _internal_result(); +} +inline void EventsResult::set_result(::mavsdk::rpc::events::EventsResult_Result value) { + _internal_set_result(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.EventsResult.result) +} +inline ::mavsdk::rpc::events::EventsResult_Result EventsResult::_internal_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::events::EventsResult_Result>(_impl_.result_); +} +inline void EventsResult::_internal_set_result(::mavsdk::rpc::events::EventsResult_Result value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.result_ = value; +} + +// string result_str = 2; +inline void EventsResult::clear_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.result_str_.ClearToEmpty(); +} +inline const std::string& EventsResult::result_str() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.EventsResult.result_str) + return _internal_result_str(); +} +template +inline PROTOBUF_ALWAYS_INLINE void EventsResult::set_result_str(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.result_str_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.events.EventsResult.result_str) +} +inline std::string* EventsResult::mutable_result_str() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_result_str(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.EventsResult.result_str) + return _s; +} +inline const std::string& EventsResult::_internal_result_str() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.result_str_.Get(); +} +inline void EventsResult::_internal_set_result_str(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.result_str_.Set(value, GetArena()); +} +inline std::string* EventsResult::_internal_mutable_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.result_str_.Mutable( GetArena()); +} +inline std::string* EventsResult::release_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.EventsResult.result_str) + return _impl_.result_str_.Release(); +} +inline void EventsResult::set_allocated_result_str(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.result_str_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.result_str_.IsDefault()) { + _impl_.result_str_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.EventsResult.result_str) +} + +// ------------------------------------------------------------------- + +// SubscribeEventsRequest + +// ------------------------------------------------------------------- + +// EventsResponse + +// .mavsdk.rpc.events.Event event = 1; +inline bool EventsResponse::has_event() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.event_ != nullptr); + return value; +} +inline void EventsResponse::clear_event() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.event_ != nullptr) _impl_.event_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::events::Event& EventsResponse::_internal_event() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::events::Event* p = _impl_.event_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::events::_Event_default_instance_); +} +inline const ::mavsdk::rpc::events::Event& EventsResponse::event() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.EventsResponse.event) + return _internal_event(); +} +inline void EventsResponse::unsafe_arena_set_allocated_event(::mavsdk::rpc::events::Event* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.event_); + } + _impl_.event_ = reinterpret_cast<::mavsdk::rpc::events::Event*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.events.EventsResponse.event) +} +inline ::mavsdk::rpc::events::Event* EventsResponse::release_event() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::events::Event* released = _impl_.event_; + _impl_.event_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::events::Event* EventsResponse::unsafe_arena_release_event() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.EventsResponse.event) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::events::Event* temp = _impl_.event_; + _impl_.event_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::events::Event* EventsResponse::_internal_mutable_event() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.event_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::events::Event>(GetArena()); + _impl_.event_ = reinterpret_cast<::mavsdk::rpc::events::Event*>(p); + } + return _impl_.event_; +} +inline ::mavsdk::rpc::events::Event* EventsResponse::mutable_event() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::events::Event* _msg = _internal_mutable_event(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.EventsResponse.event) + return _msg; +} +inline void EventsResponse::set_allocated_event(::mavsdk::rpc::events::Event* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::events::Event*>(_impl_.event_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::events::Event*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.event_ = reinterpret_cast<::mavsdk::rpc::events::Event*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.EventsResponse.event) +} + +// ------------------------------------------------------------------- + +// SubscribeHealthAndArmingChecksRequest + +// ------------------------------------------------------------------- + +// HealthAndArmingChecksResponse + +// .mavsdk.rpc.events.HealthAndArmingCheckReport report = 1; +inline bool HealthAndArmingChecksResponse::has_report() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.report_ != nullptr); + return value; +} +inline void HealthAndArmingChecksResponse::clear_report() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.report_ != nullptr) _impl_.report_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::events::HealthAndArmingCheckReport& HealthAndArmingChecksResponse::_internal_report() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::events::HealthAndArmingCheckReport* p = _impl_.report_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::events::_HealthAndArmingCheckReport_default_instance_); +} +inline const ::mavsdk::rpc::events::HealthAndArmingCheckReport& HealthAndArmingChecksResponse::report() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.HealthAndArmingChecksResponse.report) + return _internal_report(); +} +inline void HealthAndArmingChecksResponse::unsafe_arena_set_allocated_report(::mavsdk::rpc::events::HealthAndArmingCheckReport* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.report_); + } + _impl_.report_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.events.HealthAndArmingChecksResponse.report) +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckReport* HealthAndArmingChecksResponse::release_report() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::events::HealthAndArmingCheckReport* released = _impl_.report_; + _impl_.report_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckReport* HealthAndArmingChecksResponse::unsafe_arena_release_report() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.HealthAndArmingChecksResponse.report) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::events::HealthAndArmingCheckReport* temp = _impl_.report_; + _impl_.report_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckReport* HealthAndArmingChecksResponse::_internal_mutable_report() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.report_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::events::HealthAndArmingCheckReport>(GetArena()); + _impl_.report_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(p); + } + return _impl_.report_; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckReport* HealthAndArmingChecksResponse::mutable_report() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::events::HealthAndArmingCheckReport* _msg = _internal_mutable_report(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.HealthAndArmingChecksResponse.report) + return _msg; +} +inline void HealthAndArmingChecksResponse::set_allocated_report(::mavsdk::rpc::events::HealthAndArmingCheckReport* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(_impl_.report_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.report_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.HealthAndArmingChecksResponse.report) +} + +// ------------------------------------------------------------------- + +// GetHealthAndArmingChecksReportRequest + +// ------------------------------------------------------------------- + +// GetHealthAndArmingChecksReportResponse + +// .mavsdk.rpc.events.EventsResult events_result = 1; +inline bool GetHealthAndArmingChecksReportResponse::has_events_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.events_result_ != nullptr); + return value; +} +inline void GetHealthAndArmingChecksReportResponse::clear_events_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.events_result_ != nullptr) _impl_.events_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::events::EventsResult& GetHealthAndArmingChecksReportResponse::_internal_events_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::events::EventsResult* p = _impl_.events_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::events::_EventsResult_default_instance_); +} +inline const ::mavsdk::rpc::events::EventsResult& GetHealthAndArmingChecksReportResponse::events_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.events_result) + return _internal_events_result(); +} +inline void GetHealthAndArmingChecksReportResponse::unsafe_arena_set_allocated_events_result(::mavsdk::rpc::events::EventsResult* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.events_result_); + } + _impl_.events_result_ = reinterpret_cast<::mavsdk::rpc::events::EventsResult*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.events_result) +} +inline ::mavsdk::rpc::events::EventsResult* GetHealthAndArmingChecksReportResponse::release_events_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::events::EventsResult* released = _impl_.events_result_; + _impl_.events_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::events::EventsResult* GetHealthAndArmingChecksReportResponse::unsafe_arena_release_events_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.events_result) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::events::EventsResult* temp = _impl_.events_result_; + _impl_.events_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::events::EventsResult* GetHealthAndArmingChecksReportResponse::_internal_mutable_events_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.events_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::events::EventsResult>(GetArena()); + _impl_.events_result_ = reinterpret_cast<::mavsdk::rpc::events::EventsResult*>(p); + } + return _impl_.events_result_; +} +inline ::mavsdk::rpc::events::EventsResult* GetHealthAndArmingChecksReportResponse::mutable_events_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::events::EventsResult* _msg = _internal_mutable_events_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.events_result) + return _msg; +} +inline void GetHealthAndArmingChecksReportResponse::set_allocated_events_result(::mavsdk::rpc::events::EventsResult* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::events::EventsResult*>(_impl_.events_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::events::EventsResult*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.events_result_ = reinterpret_cast<::mavsdk::rpc::events::EventsResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.events_result) +} + +// .mavsdk.rpc.events.HealthAndArmingCheckReport report = 2; +inline bool GetHealthAndArmingChecksReportResponse::has_report() const { + bool value = (_impl_._has_bits_[0] & 0x00000002u) != 0; + PROTOBUF_ASSUME(!value || _impl_.report_ != nullptr); + return value; +} +inline void GetHealthAndArmingChecksReportResponse::clear_report() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.report_ != nullptr) _impl_.report_->Clear(); + _impl_._has_bits_[0] &= ~0x00000002u; +} +inline const ::mavsdk::rpc::events::HealthAndArmingCheckReport& GetHealthAndArmingChecksReportResponse::_internal_report() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::events::HealthAndArmingCheckReport* p = _impl_.report_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::events::_HealthAndArmingCheckReport_default_instance_); +} +inline const ::mavsdk::rpc::events::HealthAndArmingCheckReport& GetHealthAndArmingChecksReportResponse::report() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.report) + return _internal_report(); +} +inline void GetHealthAndArmingChecksReportResponse::unsafe_arena_set_allocated_report(::mavsdk::rpc::events::HealthAndArmingCheckReport* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.report_); + } + _impl_.report_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000002u; + } else { + _impl_._has_bits_[0] &= ~0x00000002u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.report) +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckReport* GetHealthAndArmingChecksReportResponse::release_report() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::events::HealthAndArmingCheckReport* released = _impl_.report_; + _impl_.report_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckReport* GetHealthAndArmingChecksReportResponse::unsafe_arena_release_report() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.report) + + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::events::HealthAndArmingCheckReport* temp = _impl_.report_; + _impl_.report_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckReport* GetHealthAndArmingChecksReportResponse::_internal_mutable_report() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000002u; + if (_impl_.report_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::events::HealthAndArmingCheckReport>(GetArena()); + _impl_.report_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(p); + } + return _impl_.report_; +} +inline ::mavsdk::rpc::events::HealthAndArmingCheckReport* GetHealthAndArmingChecksReportResponse::mutable_report() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::events::HealthAndArmingCheckReport* _msg = _internal_mutable_report(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.report) + return _msg; +} +inline void GetHealthAndArmingChecksReportResponse::set_allocated_report(::mavsdk::rpc::events::HealthAndArmingCheckReport* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(_impl_.report_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000002u; + } else { + _impl_._has_bits_[0] &= ~0x00000002u; + } + + _impl_.report_ = reinterpret_cast<::mavsdk::rpc::events::HealthAndArmingCheckReport*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse.report) +} + +#ifdef __GNUC__ +#pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) +} // namespace events +} // namespace rpc +} // namespace mavsdk + + +namespace google { +namespace protobuf { + +template <> +struct is_proto_enum<::mavsdk::rpc::events::EventsResult_Result> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::events::EventsResult_Result>() { + return ::mavsdk::rpc::events::EventsResult_Result_descriptor(); +} +template <> +struct is_proto_enum<::mavsdk::rpc::events::LogLevel> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::events::LogLevel>() { + return ::mavsdk::rpc::events::LogLevel_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#include "google/protobuf/port_undef.inc" + +#endif // GOOGLE_PROTOBUF_INCLUDED_events_2fevents_2eproto_2epb_2eh diff --git a/src/mavsdk_server/src/grpc_server.cpp b/src/mavsdk_server/src/grpc_server.cpp index 85d611a48..d1eb879f9 100644 --- a/src/mavsdk_server/src/grpc_server.cpp +++ b/src/mavsdk_server/src/grpc_server.cpp @@ -54,6 +54,10 @@ int GrpcServer::run() builder.RegisterService(&_component_metadata_server_service); #endif +#ifdef EVENTS_ENABLED + builder.RegisterService(&_events_service); +#endif + #ifdef FAILURE_ENABLED builder.RegisterService(&_failure_service); #endif @@ -221,6 +225,10 @@ void GrpcServer::stop() _component_metadata_server_service.stop(); #endif +#ifdef EVENTS_ENABLED + _events_service.stop(); +#endif + #ifdef FAILURE_ENABLED _failure_service.stop(); #endif diff --git a/src/mavsdk_server/src/grpc_server.h b/src/mavsdk_server/src/grpc_server.h index df0f8f52e..deb402525 100644 --- a/src/mavsdk_server/src/grpc_server.h +++ b/src/mavsdk_server/src/grpc_server.h @@ -54,6 +54,11 @@ #include "component_metadata_server/component_metadata_server_service_impl.h" #endif +#ifdef EVENTS_ENABLED +#include "plugins/events/events.h" +#include "events/events_service_impl.h" +#endif + #ifdef FAILURE_ENABLED #include "plugins/failure/failure.h" #include "failure/failure_service_impl.h" @@ -232,6 +237,11 @@ class GrpcServer { _component_metadata_server_service(_component_metadata_server_lazy_plugin), #endif +#ifdef EVENTS_ENABLED + _events_lazy_plugin(mavsdk), + _events_service(_events_lazy_plugin), +#endif + #ifdef FAILURE_ENABLED _failure_lazy_plugin(mavsdk), _failure_service(_failure_lazy_plugin), @@ -430,6 +440,13 @@ class GrpcServer { ComponentMetadataServerServiceImpl<> _component_metadata_server_service; #endif +#ifdef EVENTS_ENABLED + + LazyPlugin _events_lazy_plugin; + + EventsServiceImpl<> _events_service; +#endif + #ifdef FAILURE_ENABLED LazyPlugin _failure_lazy_plugin; diff --git a/src/mavsdk_server/src/plugins/events/events_service_impl.h b/src/mavsdk_server/src/plugins/events/events_service_impl.h new file mode 100644 index 000000000..06f33a617 --- /dev/null +++ b/src/mavsdk_server/src/plugins/events/events_service_impl.h @@ -0,0 +1,490 @@ +// 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/events/events.proto) + +#include "events/events.grpc.pb.h" +#include "plugins/events/events.h" + +#include "mavsdk.h" + +#include "lazy_plugin.h" + +#include "log.h" +#include +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace mavsdk_server { + +template> + +class EventsServiceImpl final : public rpc::events::EventsService::Service { +public: + EventsServiceImpl(LazyPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) {} + + template + void fillResponseWithResult(ResponseType* response, mavsdk::Events::Result& result) const + { + auto rpc_result = translateToRpcResult(result); + + auto* rpc_events_result = new rpc::events::EventsResult(); + rpc_events_result->set_result(rpc_result); + std::stringstream ss; + ss << result; + rpc_events_result->set_result_str(ss.str()); + + response->set_allocated_events_result(rpc_events_result); + } + + static rpc::events::LogLevel translateToRpcLogLevel(const mavsdk::Events::LogLevel& log_level) + { + switch (log_level) { + default: + LogErr() << "Unknown log_level enum value: " << static_cast(log_level); + // FALLTHROUGH + case mavsdk::Events::LogLevel::Emergency: + return rpc::events::LOG_LEVEL_EMERGENCY; + case mavsdk::Events::LogLevel::Alert: + return rpc::events::LOG_LEVEL_ALERT; + case mavsdk::Events::LogLevel::Critical: + return rpc::events::LOG_LEVEL_CRITICAL; + case mavsdk::Events::LogLevel::Error: + return rpc::events::LOG_LEVEL_ERROR; + case mavsdk::Events::LogLevel::Warning: + return rpc::events::LOG_LEVEL_WARNING; + case mavsdk::Events::LogLevel::Notice: + return rpc::events::LOG_LEVEL_NOTICE; + case mavsdk::Events::LogLevel::Info: + return rpc::events::LOG_LEVEL_INFO; + case mavsdk::Events::LogLevel::Debug: + return rpc::events::LOG_LEVEL_DEBUG; + } + } + + static mavsdk::Events::LogLevel translateFromRpcLogLevel(const rpc::events::LogLevel log_level) + { + switch (log_level) { + default: + LogErr() << "Unknown log_level enum value: " << static_cast(log_level); + // FALLTHROUGH + case rpc::events::LOG_LEVEL_EMERGENCY: + return mavsdk::Events::LogLevel::Emergency; + case rpc::events::LOG_LEVEL_ALERT: + return mavsdk::Events::LogLevel::Alert; + case rpc::events::LOG_LEVEL_CRITICAL: + return mavsdk::Events::LogLevel::Critical; + case rpc::events::LOG_LEVEL_ERROR: + return mavsdk::Events::LogLevel::Error; + case rpc::events::LOG_LEVEL_WARNING: + return mavsdk::Events::LogLevel::Warning; + case rpc::events::LOG_LEVEL_NOTICE: + return mavsdk::Events::LogLevel::Notice; + case rpc::events::LOG_LEVEL_INFO: + return mavsdk::Events::LogLevel::Info; + case rpc::events::LOG_LEVEL_DEBUG: + return mavsdk::Events::LogLevel::Debug; + } + } + + static std::unique_ptr + translateToRpcEvent(const mavsdk::Events::Event& event) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_compid(event.compid); + + rpc_obj->set_message(event.message); + + rpc_obj->set_description(event.description); + + rpc_obj->set_log_level(translateToRpcLogLevel(event.log_level)); + + rpc_obj->set_event_namespace(event.event_namespace); + + rpc_obj->set_event_name(event.event_name); + + return rpc_obj; + } + + static mavsdk::Events::Event translateFromRpcEvent(const rpc::events::Event& event) + { + mavsdk::Events::Event obj; + + obj.compid = event.compid(); + + obj.message = event.message(); + + obj.description = event.description(); + + obj.log_level = translateFromRpcLogLevel(event.log_level()); + + obj.event_namespace = event.event_namespace(); + + obj.event_name = event.event_name(); + + return obj; + } + + static std::unique_ptr + translateToRpcHealthAndArmingCheckProblem( + const mavsdk::Events::HealthAndArmingCheckProblem& health_and_arming_check_problem) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_message(health_and_arming_check_problem.message); + + rpc_obj->set_description(health_and_arming_check_problem.description); + + rpc_obj->set_log_level(translateToRpcLogLevel(health_and_arming_check_problem.log_level)); + + rpc_obj->set_health_component(health_and_arming_check_problem.health_component); + + return rpc_obj; + } + + static mavsdk::Events::HealthAndArmingCheckProblem translateFromRpcHealthAndArmingCheckProblem( + const rpc::events::HealthAndArmingCheckProblem& health_and_arming_check_problem) + { + mavsdk::Events::HealthAndArmingCheckProblem obj; + + obj.message = health_and_arming_check_problem.message(); + + obj.description = health_and_arming_check_problem.description(); + + obj.log_level = translateFromRpcLogLevel(health_and_arming_check_problem.log_level()); + + obj.health_component = health_and_arming_check_problem.health_component(); + + return obj; + } + + static std::unique_ptr + translateToRpcHealthAndArmingCheckMode( + const mavsdk::Events::HealthAndArmingCheckMode& health_and_arming_check_mode) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_mode_name(health_and_arming_check_mode.mode_name); + + rpc_obj->set_can_arm_or_run(health_and_arming_check_mode.can_arm_or_run); + + for (const auto& elem : health_and_arming_check_mode.problems) { + auto* ptr = rpc_obj->add_problems(); + ptr->CopyFrom(*translateToRpcHealthAndArmingCheckProblem(elem).release()); + } + + return rpc_obj; + } + + static mavsdk::Events::HealthAndArmingCheckMode translateFromRpcHealthAndArmingCheckMode( + const rpc::events::HealthAndArmingCheckMode& health_and_arming_check_mode) + { + mavsdk::Events::HealthAndArmingCheckMode obj; + + obj.mode_name = health_and_arming_check_mode.mode_name(); + + obj.can_arm_or_run = health_and_arming_check_mode.can_arm_or_run(); + + for (const auto& elem : health_and_arming_check_mode.problems()) { + obj.problems.push_back(translateFromRpcHealthAndArmingCheckProblem( + static_cast(elem))); + } + + return obj; + } + + static std::unique_ptr translateToRpcHealthComponentReport( + const mavsdk::Events::HealthComponentReport& health_component_report) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_name(health_component_report.name); + + rpc_obj->set_label(health_component_report.label); + + rpc_obj->set_is_present(health_component_report.is_present); + + rpc_obj->set_has_error(health_component_report.has_error); + + rpc_obj->set_has_warning(health_component_report.has_warning); + + return rpc_obj; + } + + static mavsdk::Events::HealthComponentReport translateFromRpcHealthComponentReport( + const rpc::events::HealthComponentReport& health_component_report) + { + mavsdk::Events::HealthComponentReport obj; + + obj.name = health_component_report.name(); + + obj.label = health_component_report.label(); + + obj.is_present = health_component_report.is_present(); + + obj.has_error = health_component_report.has_error(); + + obj.has_warning = health_component_report.has_warning(); + + return obj; + } + + static std::unique_ptr + translateToRpcHealthAndArmingCheckReport( + const mavsdk::Events::HealthAndArmingCheckReport& health_and_arming_check_report) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_allocated_current_mode_intention( + translateToRpcHealthAndArmingCheckMode( + health_and_arming_check_report.current_mode_intention) + .release()); + + for (const auto& elem : health_and_arming_check_report.health_components) { + auto* ptr = rpc_obj->add_health_components(); + ptr->CopyFrom(*translateToRpcHealthComponentReport(elem).release()); + } + + for (const auto& elem : health_and_arming_check_report.all_problems) { + auto* ptr = rpc_obj->add_all_problems(); + ptr->CopyFrom(*translateToRpcHealthAndArmingCheckProblem(elem).release()); + } + + return rpc_obj; + } + + static mavsdk::Events::HealthAndArmingCheckReport translateFromRpcHealthAndArmingCheckReport( + const rpc::events::HealthAndArmingCheckReport& health_and_arming_check_report) + { + mavsdk::Events::HealthAndArmingCheckReport obj; + + obj.current_mode_intention = translateFromRpcHealthAndArmingCheckMode( + health_and_arming_check_report.current_mode_intention()); + + for (const auto& elem : health_and_arming_check_report.health_components()) { + obj.health_components.push_back(translateFromRpcHealthComponentReport( + static_cast(elem))); + } + + for (const auto& elem : health_and_arming_check_report.all_problems()) { + obj.all_problems.push_back(translateFromRpcHealthAndArmingCheckProblem( + static_cast(elem))); + } + + return obj; + } + + static rpc::events::EventsResult::Result + translateToRpcResult(const mavsdk::Events::Result& result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case mavsdk::Events::Result::Success: + return rpc::events::EventsResult_Result_RESULT_SUCCESS; + case mavsdk::Events::Result::NotAvailable: + return rpc::events::EventsResult_Result_RESULT_NOT_AVAILABLE; + case mavsdk::Events::Result::ConnectionError: + return rpc::events::EventsResult_Result_RESULT_CONNECTION_ERROR; + case mavsdk::Events::Result::Unsupported: + return rpc::events::EventsResult_Result_RESULT_UNSUPPORTED; + case mavsdk::Events::Result::Denied: + return rpc::events::EventsResult_Result_RESULT_DENIED; + case mavsdk::Events::Result::Failed: + return rpc::events::EventsResult_Result_RESULT_FAILED; + case mavsdk::Events::Result::Timeout: + return rpc::events::EventsResult_Result_RESULT_TIMEOUT; + case mavsdk::Events::Result::NoSystem: + return rpc::events::EventsResult_Result_RESULT_NO_SYSTEM; + } + } + + static mavsdk::Events::Result + translateFromRpcResult(const rpc::events::EventsResult::Result result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case rpc::events::EventsResult_Result_RESULT_SUCCESS: + return mavsdk::Events::Result::Success; + case rpc::events::EventsResult_Result_RESULT_NOT_AVAILABLE: + return mavsdk::Events::Result::NotAvailable; + case rpc::events::EventsResult_Result_RESULT_CONNECTION_ERROR: + return mavsdk::Events::Result::ConnectionError; + case rpc::events::EventsResult_Result_RESULT_UNSUPPORTED: + return mavsdk::Events::Result::Unsupported; + case rpc::events::EventsResult_Result_RESULT_DENIED: + return mavsdk::Events::Result::Denied; + case rpc::events::EventsResult_Result_RESULT_FAILED: + return mavsdk::Events::Result::Failed; + case rpc::events::EventsResult_Result_RESULT_TIMEOUT: + return mavsdk::Events::Result::Timeout; + case rpc::events::EventsResult_Result_RESULT_NO_SYSTEM: + return mavsdk::Events::Result::NoSystem; + } + } + + grpc::Status SubscribeEvents( + grpc::ServerContext* /* context */, + const mavsdk::rpc::events::SubscribeEventsRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::Events::EventsHandle handle = _lazy_plugin.maybe_plugin()->subscribe_events( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::Events::Event events) { + rpc::events::EventsResponse rpc_response; + + rpc_response.set_allocated_event(translateToRpcEvent(events).release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_events(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status SubscribeHealthAndArmingChecks( + grpc::ServerContext* /* context */, + const mavsdk::rpc::events::SubscribeHealthAndArmingChecksRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::Events::HealthAndArmingChecksHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_health_and_arming_checks( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::Events::HealthAndArmingCheckReport health_and_arming_checks) { + rpc::events::HealthAndArmingChecksResponse rpc_response; + + rpc_response.set_allocated_report( + translateToRpcHealthAndArmingCheckReport(health_and_arming_checks) + .release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_health_and_arming_checks(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status GetHealthAndArmingChecksReport( + grpc::ServerContext* /* context */, + const rpc::events::GetHealthAndArmingChecksReportRequest* /* request */, + rpc::events::GetHealthAndArmingChecksReportResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::Events::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->get_health_and_arming_checks_report(); + + if (response != nullptr) { + fillResponseWithResult(response, result.first); + + response->set_allocated_report( + translateToRpcHealthAndArmingCheckReport(result.second).release()); + } + + return grpc::Status::OK; + } + + void stop() + { + _stopped.store(true); + std::lock_guard lock(_stream_stop_mutex); + 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 { + std::lock_guard lock(_stream_stop_mutex); + _stream_stop_promises.push_back(prom); + } + } + + void unregister_stream_stop_promise(std::shared_ptr> prom) + { + std::lock_guard lock(_stream_stop_mutex); + 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::mutex _stream_stop_mutex{}; + std::vector>> _stream_stop_promises{}; +}; + +} // namespace mavsdk_server +} // namespace mavsdk \ No newline at end of file diff --git a/src/plugins.txt b/src/plugins.txt index 5b058230f..874dec935 100644 --- a/src/plugins.txt +++ b/src/plugins.txt @@ -6,6 +6,7 @@ camera camera_server component_metadata component_metadata_server +events failure follow_me ftp diff --git a/third_party/CMakeLists.txt b/third_party/CMakeLists.txt index e19d73927..d3171eea6 100644 --- a/third_party/CMakeLists.txt +++ b/third_party/CMakeLists.txt @@ -4,10 +4,10 @@ project(third_party) include(cmake/build_target.cmake) -if (SUPERBUILD) - list(APPEND CMAKE_PREFIX_PATH "${DEPS_INSTALL_PATH}") - set(CMAKE_PREFIX_PATH ${CMAKE_PREFIX_PATH} PARENT_SCOPE) +list(APPEND CMAKE_PREFIX_PATH "${DEPS_INSTALL_PATH}") +set(CMAKE_PREFIX_PATH ${CMAKE_PREFIX_PATH} PARENT_SCOPE) +if (SUPERBUILD) build_target(mavlink) build_target(jsoncpp) build_target(tinyxml2) @@ -33,8 +33,8 @@ if (SUPERBUILD) endif() +build_target(libevents) + if (ENABLE_CPPTRACE) - list(APPEND CMAKE_PREFIX_PATH "${DEPS_INSTALL_PATH}") - set(CMAKE_PREFIX_PATH ${CMAKE_PREFIX_PATH} PARENT_SCOPE) build_target(cpptrace) endif() diff --git a/third_party/libevents/CMakeLists.txt b/third_party/libevents/CMakeLists.txt new file mode 100644 index 000000000..8e5309345 --- /dev/null +++ b/third_party/libevents/CMakeLists.txt @@ -0,0 +1,38 @@ +cmake_minimum_required(VERSION 3.7) + +project(external-libevents) +include(ExternalProject) + +list(APPEND CMAKE_ARGS + "-DCMAKE_PREFIX_PATH:PATH=${CMAKE_PREFIX_PATH}" + "-DCMAKE_INSTALL_PREFIX:PATH=${CMAKE_INSTALL_PREFIX}" + "-DCMAKE_TOOLCHAIN_FILE:PATH=${CMAKE_TOOLCHAIN_FILE}" + "-DCMAKE_POSITION_INDEPENDENT_CODE=ON" + "-DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}" + "-DBUILD_SHARED_LIBS=OFF" + "-DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR}" + "-DCMAKE_DEBUG_POSTFIX=d" + "-DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION}" + "-DENABLE_TESTING=OFF" + ) + +if(IOS) + list(APPEND CMAKE_ARGS + "-DPLATFORM=${PLATFORM}" + "-DDEPLOYMENT_TARGET=${DEPLOYMENT_TARGET}" + "-DENABLE_STRICT_TRY_COMPILE=${ENABLE_STRICT_TRY_COMPILE}" + ) +endif() + +message(STATUS "Preparing external project \"libevents\" with args:") +foreach(CMAKE_ARG ${CMAKE_ARGS}) + message(STATUS "-- ${CMAKE_ARG}") +endforeach() + +ExternalProject_Add( + libevents + GIT_REPOSITORY https://github.com/mavlink/libevents.git + GIT_TAG 9474657606d13301d426e044450c4f84de2221be + SOURCE_SUBDIR libs/cpp + CMAKE_ARGS "${CMAKE_ARGS}" +) \ No newline at end of file From c7acf9e7f8dabde0631c6eb787cda14ba0683929 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 11 Jun 2024 13:53:47 +0200 Subject: [PATCH 6/9] examples: add events example (listen for events & health report) --- examples/events/CMakeLists.txt | 22 +++++++ examples/events/events.cpp | 115 +++++++++++++++++++++++++++++++++ 2 files changed, 137 insertions(+) create mode 100644 examples/events/CMakeLists.txt create mode 100644 examples/events/events.cpp diff --git a/examples/events/CMakeLists.txt b/examples/events/CMakeLists.txt new file mode 100644 index 000000000..9cbcab49c --- /dev/null +++ b/examples/events/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(events) + +add_executable(events + events.cpp +) + +find_package(MAVSDK REQUIRED) + +target_link_libraries(events + MAVSDK::mavsdk +) + +if(NOT MSVC) + add_compile_options(events PRIVATE -Wall -Wextra) +else() + add_compile_options(events PRIVATE -W2) +endif() diff --git a/examples/events/events.cpp b/examples/events/events.cpp new file mode 100644 index 000000000..92d700cb5 --- /dev/null +++ b/examples/events/events.cpp @@ -0,0 +1,115 @@ +// +// Simple example to demonstrate how to use the events plugin. +// + +#include +#include +#include +#include +#include +#include + +using namespace mavsdk; + +void usage(const std::string& bin_name) +{ + std::cerr << "Usage : " << bin_name << " [-v] [monitor]\n" + << "Connection URL format should be:\n" + << " For TCP : tcp://[server_host][:server_port]\n" + << " For UDP : udp://[bind_host][:bind_port]\n" + << " For Serial : serial:///path/to/serial/dev[:baudrate]\n" + << "For example, to connect to the simulator use URL: udp://:14540\n\n" + << " -v: enable verbose output\n" + << " monitor: listen for events (instead of printing the arming report)\n"; +} + +int main(int argc, char** argv) +{ + if (argc < 2) { + usage(argv[0]); + return 1; + } + + // Parse CLI arguments + bool monitor = false; + bool verbose = false; + for (int i = 2; i < argc; ++i) { + if (strcmp(argv[i], "-v") == 0) { + verbose = true; + } else if (strcmp(argv[i], "monitor") == 0) { + monitor = true; + } + } + + Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); + + if (connection_result != ConnectionResult::Success) { + std::cerr << "Connection failed: " << connection_result << '\n'; + return 1; + } + + auto system = mavsdk.first_autopilot(3.0); + if (!system) { + std::cerr << "Timed out waiting for system\n"; + return 1; + } + + auto events = Events{*system}; + + if (monitor) { + // Listen for events + events.subscribe_events([verbose](const Events::Event& event) { + std::cout << "[" << event.log_level << "] " << event.message << std::endl; + if (verbose) { + if (!event.description.empty()) { + std::cout << " Description: " << event.description << std::endl; + } + std::cout << " Event name: " << event.event_namespace << "/" << event.event_name + << std::endl; + } + }); + while (true) { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + } else { + // Listen for arming checks report + const auto telemetry = Telemetry{*system}; + std::promise promise; + auto future = promise.get_future(); + bool reported = false; + events.subscribe_health_and_arming_checks( + [&telemetry, &promise, &verbose, &reported]( + const Events::HealthAndArmingCheckReport& report) { + if (reported) { // Report only once + return; + } + reported = true; + std::cout << "Current Mode (intention): " << report.current_mode_intention.mode_name + << std::endl; + const std::string can_arm_or_run = telemetry.armed() ? "Can Run: " : "Can Arm: "; + std::cout << can_arm_or_run + << (report.current_mode_intention.can_arm_or_run ? "yes" : "No") + << std::endl; + if (!report.current_mode_intention.problems.empty()) { + std::cout << "Reports:" << std::endl; + for (const auto& problem : report.current_mode_intention.problems) { + std::cout << " [" << problem.log_level << "] [" << problem.health_component + << "]: " << problem.message << std::endl; + } + } + + if (verbose && !report.all_problems.empty()) { + std::cout << "All Reports:" << std::endl; + for (const auto& problem : report.all_problems) { + std::cout << " [" << problem.log_level << "] [" << problem.health_component + << "]: " << problem.message << std::endl; + } + } + promise.set_value(true); + }); + future.get(); + } + + return 0; +} From 13b03ec5418f78b18671a1ec15a6a8c520e77db5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 11 Jun 2024 16:06:35 +0200 Subject: [PATCH 7/9] src: add missing include MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes errors in the form of: MAVSDK/src/mavsdk/core/call_every_handler.cpp:33:20: error: ‘find_if’ is not a member of ‘std’ This is with GCC 14.1.1 --- src/integration_tests/camera_capture_info.cpp | 1 + src/integration_tests/integration_test_helper.h | 1 + src/mavsdk/core/call_every_handler.cpp | 1 + src/mavsdk/core/callback_list_impl.h | 1 + src/mavsdk/core/mavlink_request_message_handler.cpp | 1 + src/mavsdk/core/timeout_handler.cpp | 1 + src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp | 1 + 7 files changed, 7 insertions(+) diff --git a/src/integration_tests/camera_capture_info.cpp b/src/integration_tests/camera_capture_info.cpp index f72d2ebf3..137135fbd 100644 --- a/src/integration_tests/camera_capture_info.cpp +++ b/src/integration_tests/camera_capture_info.cpp @@ -1,5 +1,6 @@ #include "integration_test_helper.h" #include "mavsdk.h" +#include #include #include #include diff --git a/src/integration_tests/integration_test_helper.h b/src/integration_tests/integration_test_helper.h index d2863abe1..2751510b6 100644 --- a/src/integration_tests/integration_test_helper.h +++ b/src/integration_tests/integration_test_helper.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include #include diff --git a/src/mavsdk/core/call_every_handler.cpp b/src/mavsdk/core/call_every_handler.cpp index fce675d74..d6f908c0a 100644 --- a/src/mavsdk/core/call_every_handler.cpp +++ b/src/mavsdk/core/call_every_handler.cpp @@ -1,6 +1,7 @@ #include "call_every_handler.h" #include +#include namespace mavsdk { diff --git a/src/mavsdk/core/callback_list_impl.h b/src/mavsdk/core/callback_list_impl.h index 7bd8c16c4..15f312454 100644 --- a/src/mavsdk/core/callback_list_impl.h +++ b/src/mavsdk/core/callback_list_impl.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include #include diff --git a/src/mavsdk/core/mavlink_request_message_handler.cpp b/src/mavsdk/core/mavlink_request_message_handler.cpp index 89a976a1f..a9382e189 100644 --- a/src/mavsdk/core/mavlink_request_message_handler.cpp +++ b/src/mavsdk/core/mavlink_request_message_handler.cpp @@ -3,6 +3,7 @@ #include "server_component_impl.h" #include "mavlink_command_receiver.h" #include "log.h" +#include namespace mavsdk { diff --git a/src/mavsdk/core/timeout_handler.cpp b/src/mavsdk/core/timeout_handler.cpp index 17870d680..6065b31ab 100644 --- a/src/mavsdk/core/timeout_handler.cpp +++ b/src/mavsdk/core/timeout_handler.cpp @@ -1,4 +1,5 @@ #include "timeout_handler.h" +#include namespace mavsdk { diff --git a/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp b/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp index 132c2467d..1f59dc710 100644 --- a/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp +++ b/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp @@ -1,6 +1,7 @@ #include "telemetry_server_impl.h" #include "unused.h" #include +#include namespace mavsdk { From 5803c2224cbd9b992ac5188c4655a047ecd5d405 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 15 Jul 2024 20:09:51 +0200 Subject: [PATCH 8/9] proto: Update submodule --- proto | 2 +- src/mavsdk/plugins/events/include/plugins/events/events.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/proto b/proto index 1cd12e921..d708453bc 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 1cd12e9212ab1a7405e5f6d8dc432ad47d9977ef +Subproject commit d708453bce56a1b6aaae3f5185d3d377bd701038 diff --git a/src/mavsdk/plugins/events/include/plugins/events/events.h b/src/mavsdk/plugins/events/include/plugins/events/events.h index 04d900191..a06e555ee 100644 --- a/src/mavsdk/plugins/events/include/plugins/events/events.h +++ b/src/mavsdk/plugins/events/include/plugins/events/events.h @@ -140,7 +140,7 @@ class Events : public PluginBase { */ struct HealthAndArmingCheckMode { std::string mode_name{}; /**< @brief Mode name, e.g. "Position" */ - bool can_arm_or_run{}; /**< @brief If disarmed: indicated if arming is possible. If armed: + bool can_arm_or_run{}; /**< @brief If disarmed: indicates if arming is possible. If armed: indicates if the mode can be selected */ std::vector problems{}; /**< @brief List of reported problems for the mode */ From f80591452ad03d014e36970769e2c1b7df7236e2 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 15 Jul 2024 20:10:42 +0200 Subject: [PATCH 9/9] core: Call download on thread pool This is to avoid locking us out when doing subsequent downloads. For some reason this locked up on certain platforms. --- .../core/mavlink_component_metadata.cpp | 68 +++++++++++-------- 1 file changed, 40 insertions(+), 28 deletions(-) diff --git a/src/mavsdk/core/mavlink_component_metadata.cpp b/src/mavsdk/core/mavlink_component_metadata.cpp index 23430fe4a..f4a900178 100644 --- a/src/mavsdk/core/mavlink_component_metadata.cpp +++ b/src/mavsdk/core/mavlink_component_metadata.cpp @@ -197,35 +197,47 @@ void MavlinkComponentMetadata::retrieve_metadata(uint8_t compid, COMP_METADATA_T const std::filesystem::path local_path = tmp_download_path / std::filesystem::path(download_path).filename(); - _system_impl.mavlink_ftp_client().download_async( - download_path, - tmp_download_path.string(), - true, - [this, &component, local_path, compid, type, file_cache_tag]( - MavlinkFtpClient::ClientResult download_result, - MavlinkFtpClient::ProgressData progress_data) { - if (download_result == MavlinkFtpClient::ClientResult::Next) { - if (_verbose_debugging) { - LogDebug() - << "File download progress: " << progress_data.bytes_transferred - << '/' << progress_data.total_bytes; - } - // TODO: detect slow link (e.g. telemetry), and cancel download - // (fallback to http) e.g. by estimating the remaining download time, - // and cancel if >40s - } else { - if (_verbose_debugging) { - LogDebug() << "File download ended with result " << download_result; - } - if (download_result == MavlinkFtpClient::ClientResult::Success) { - component.current_metadata_path() = - extract_and_cache_file(local_path, file_cache_tag); + + _system_impl.call_user_callback([this, + download_path, + tmp_download_path, + &component, + target_compid, + local_path, + compid, + type, + file_cache_tag]() { + _system_impl.mavlink_ftp_client().download_async( + download_path, + tmp_download_path.string(), + true, + [this, &component, local_path, compid, type, file_cache_tag]( + MavlinkFtpClient::ClientResult download_result, + MavlinkFtpClient::ProgressData progress_data) { + if (download_result == MavlinkFtpClient::ClientResult::Next) { + if (_verbose_debugging) { + LogDebug() << "File download progress: " + << progress_data.bytes_transferred << '/' + << progress_data.total_bytes; + } + // TODO: detect slow link (e.g. telemetry), and cancel download + // (fallback to http) e.g. by estimating the remaining download + // time, and cancel if >40s + } else { + if (_verbose_debugging) { + LogDebug() + << "File download ended with result " << download_result; + } + if (download_result == MavlinkFtpClient::ClientResult::Success) { + component.current_metadata_path() = + extract_and_cache_file(local_path, file_cache_tag); + } + // Move on to the next uri or type + retrieve_metadata(compid, type); } - // Move on to the next uri or type - retrieve_metadata(compid, type); - } - }, - target_compid); + }, + target_compid); + }); } else { // http(s) download