From c5e85d611e324a5216af2774385a7854ecc3aece Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 4 Apr 2024 11:26:42 +0200 Subject: [PATCH 01/15] mavlink_ftp_client: allow specifying the target component id per request --- src/mavsdk/core/mavlink_ftp_client.cpp | 79 +++++++++++++------------- src/mavsdk/core/mavlink_ftp_client.h | 11 +++- 2 files changed, 49 insertions(+), 41 deletions(-) diff --git a/src/mavsdk/core/mavlink_ftp_client.cpp b/src/mavsdk/core/mavlink_ftp_client.cpp index 77e1834946..0d1075326a 100644 --- a/src/mavsdk/core/mavlink_ftp_client.cpp +++ b/src/mavsdk/core/mavlink_ftp_client.cpp @@ -381,7 +381,7 @@ bool MavlinkFtpClient::download_start(Work& work, DownloadItem& item) work.payload.size = item.remote_path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -437,7 +437,7 @@ bool MavlinkFtpClient::download_continue(Work& work, DownloadItem& item, Payload } start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } else { @@ -457,7 +457,7 @@ bool MavlinkFtpClient::download_continue(Work& work, DownloadItem& item, Payload work.payload.size = 0; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); } return true; @@ -489,7 +489,7 @@ bool MavlinkFtpClient::download_burst_start(Work& work, DownloadBurstItem& item) work.payload.size = item.remote_path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -666,7 +666,7 @@ void MavlinkFtpClient::download_burst_end(Work& work) work.payload.size = 0; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); } void MavlinkFtpClient::request_burst(Work& work, DownloadBurstItem& item) @@ -684,7 +684,7 @@ void MavlinkFtpClient::request_burst(Work& work, DownloadBurstItem& item) work.payload.size = max_data_length; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); } void MavlinkFtpClient::request_next_rest(Work& work, DownloadBurstItem& item) @@ -706,7 +706,7 @@ void MavlinkFtpClient::request_next_rest(Work& work, DownloadBurstItem& item) work.payload.size = size; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); } size_t MavlinkFtpClient::burst_bytes_transferred(DownloadBurstItem& item) @@ -762,7 +762,7 @@ bool MavlinkFtpClient::upload_start(Work& work, UploadItem& item) work.payload.size = remote_file_path.string().size() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -796,7 +796,7 @@ bool MavlinkFtpClient::upload_continue(Work& work, UploadItem& item) item.bytes_transferred += bytes_read; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); } else { // Final step @@ -811,7 +811,7 @@ bool MavlinkFtpClient::upload_continue(Work& work, UploadItem& item) work.payload.size = 0; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); } item.callback( @@ -839,7 +839,7 @@ bool MavlinkFtpClient::remove_start(Work& work, RemoveItem& item) work.payload.size = item.path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -867,7 +867,7 @@ bool MavlinkFtpClient::rename_start(Work& work, RenameItem& item) work.payload.size += item.to_path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -889,7 +889,7 @@ bool MavlinkFtpClient::create_dir_start(Work& work, CreateDirItem& item) work.payload.size = item.path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -911,7 +911,7 @@ bool MavlinkFtpClient::remove_dir_start(Work& work, RemoveDirItem& item) work.payload.size = item.path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -940,7 +940,7 @@ bool MavlinkFtpClient::compare_files_start(Work& work, CompareFilesItem& item) work.payload.size = item.remote_path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -962,7 +962,7 @@ bool MavlinkFtpClient::list_dir_start(Work& work, ListDirItem& item) work.payload.size = item.path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -1017,7 +1017,7 @@ bool MavlinkFtpClient::list_dir_continue(Work& work, ListDirItem& item, PayloadH work.payload.size = item.path.length() + 1; start_timer(); - send_mavlink_ftp_message(work.payload); + send_mavlink_ftp_message(work.payload, work.target_compid); return true; } @@ -1061,14 +1061,16 @@ void MavlinkFtpClient::download_async( const std::string& remote_path, const std::string& local_folder, bool use_burst, - DownloadCallback callback) + DownloadCallback callback, + std::optional maybe_target_compid) { if (use_burst) { auto item = DownloadBurstItem{}; item.remote_path = remote_path; item.local_folder = local_folder; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = + Work{std::move(item), maybe_target_compid.value_or(get_target_component_id())}; _work_queue.push_back(std::make_shared(std::move(new_work))); } else { @@ -1076,7 +1078,8 @@ void MavlinkFtpClient::download_async( item.remote_path = remote_path; item.local_folder = local_folder; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = + Work{std::move(item), maybe_target_compid.value_or(get_target_component_id())}; _work_queue.push_back(std::make_shared(std::move(new_work))); } } @@ -1088,7 +1091,7 @@ void MavlinkFtpClient::upload_async( item.local_file_path = local_file_path; item.remote_folder = remote_folder; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = Work{std::move(item), get_target_component_id()}; _work_queue.push_back(std::make_shared(std::move(new_work))); } @@ -1098,7 +1101,7 @@ void MavlinkFtpClient::list_directory_async(const std::string& path, ListDirecto auto item = ListDirItem{}; item.path = path; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = Work{std::move(item), get_target_component_id()}; _work_queue.push_back(std::make_shared(std::move(new_work))); } @@ -1108,7 +1111,7 @@ void MavlinkFtpClient::create_directory_async(const std::string& path, ResultCal auto item = CreateDirItem{}; item.path = path; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = Work{std::move(item), get_target_component_id()}; _work_queue.push_back(std::make_shared(std::move(new_work))); } @@ -1118,7 +1121,7 @@ void MavlinkFtpClient::remove_directory_async(const std::string& path, ResultCal auto item = RemoveDirItem{}; item.path = path; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = Work{std::move(item), get_target_component_id()}; _work_queue.push_back(std::make_shared(std::move(new_work))); } @@ -1128,7 +1131,7 @@ void MavlinkFtpClient::remove_file_async(const std::string& path, ResultCallback auto item = RemoveItem{}; item.path = path; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = Work{std::move(item), get_target_component_id()}; _work_queue.push_back(std::make_shared(std::move(new_work))); } @@ -1140,7 +1143,7 @@ void MavlinkFtpClient::rename_async( item.from_path = from_path; item.to_path = to_path; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = Work{std::move(item), get_target_component_id()}; _work_queue.push_back(std::make_shared(std::move(new_work))); } @@ -1154,12 +1157,12 @@ void MavlinkFtpClient::are_files_identical_async( item.local_path = local_path; item.remote_path = remote_path; item.callback = callback; - auto new_work = Work{std::move(item)}; + auto new_work = Work{std::move(item), get_target_component_id()}; _work_queue.push_back(std::make_shared(std::move(new_work))); } -void MavlinkFtpClient::send_mavlink_ftp_message(const PayloadHeader& payload) +void MavlinkFtpClient::send_mavlink_ftp_message(const PayloadHeader& payload, uint8_t target_compid) { _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { mavlink_message_t message; @@ -1170,7 +1173,7 @@ void MavlinkFtpClient::send_mavlink_ftp_message(const PayloadHeader& payload) &message, _network_id, _system_impl.get_system_id(), - get_target_component_id(), + target_compid, reinterpret_cast(&payload)); return message; }); @@ -1213,7 +1216,7 @@ void MavlinkFtpClient::timeout() } start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); }, [&](DownloadBurstItem& item) { if (--work->retries == 0) { @@ -1254,7 +1257,7 @@ void MavlinkFtpClient::timeout() } else { // Otherwise, start burst again. start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); } } }, @@ -1269,7 +1272,7 @@ void MavlinkFtpClient::timeout() } start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); }, [&](RemoveItem& item) { if (--work->retries == 0) { @@ -1282,7 +1285,7 @@ void MavlinkFtpClient::timeout() } start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); }, [&](RenameItem& item) { if (--work->retries == 0) { @@ -1295,7 +1298,7 @@ void MavlinkFtpClient::timeout() } start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); }, [&](CreateDirItem& item) { if (--work->retries == 0) { @@ -1308,7 +1311,7 @@ void MavlinkFtpClient::timeout() } start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); }, [&](RemoveDirItem& item) { if (--work->retries == 0) { @@ -1321,7 +1324,7 @@ void MavlinkFtpClient::timeout() } start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); }, [&](CompareFilesItem& item) { if (--work->retries == 0) { @@ -1334,7 +1337,7 @@ void MavlinkFtpClient::timeout() } start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); }, [&](ListDirItem& item) { if (--work->retries == 0) { @@ -1347,7 +1350,7 @@ void MavlinkFtpClient::timeout() } start_timer(); - send_mavlink_ftp_message(work->payload); + send_mavlink_ftp_message(work->payload, work->target_compid); }}, work->item); } diff --git a/src/mavsdk/core/mavlink_ftp_client.h b/src/mavsdk/core/mavlink_ftp_client.h index d04b44590c..4c84f4b14e 100644 --- a/src/mavsdk/core/mavlink_ftp_client.h +++ b/src/mavsdk/core/mavlink_ftp_client.h @@ -71,7 +71,8 @@ class MavlinkFtpClient { const std::string& remote_file_path, const std::string& local_folder, bool use_burst, - DownloadCallback callback); + DownloadCallback callback, + std::optional maybe_target_compid = {}); void upload_async( const std::string& local_file_path, const std::string& remote_folder, @@ -225,7 +226,11 @@ class MavlinkFtpClient { Opcode last_opcode{}; uint16_t last_received_seq_number{0}; uint16_t last_sent_seq_number{0}; - Work(Item new_item) : item(std::move(new_item)) {} + uint8_t target_compid{}; + Work(Item new_item, uint8_t target_compid_) : + item(std::move(new_item)), + target_compid(target_compid_) + {} }; /// @brief Possible server results returned for requests. @@ -300,7 +305,7 @@ class MavlinkFtpClient { ClientResult calc_local_file_crc32(const std::string& path, uint32_t& csum); static ClientResult translate(ServerResult result); - void send_mavlink_ftp_message(const PayloadHeader& payload); + void send_mavlink_ftp_message(const PayloadHeader& payload, uint8_t target_compid); uint8_t get_target_component_id(); From 1979c80a847b0bb6685fc0f14fb2107f4741ea26 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 4 Apr 2024 11:28:01 +0200 Subject: [PATCH 02/15] fix mavlink_ftp_client: close ofstream before calling the callback Otherwise there might still be data in the buffer. All other places already close the stream. --- src/mavsdk/core/mavlink_ftp_client.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/mavsdk/core/mavlink_ftp_client.cpp b/src/mavsdk/core/mavlink_ftp_client.cpp index 0d1075326a..94e04c0643 100644 --- a/src/mavsdk/core/mavlink_ftp_client.cpp +++ b/src/mavsdk/core/mavlink_ftp_client.cpp @@ -1236,6 +1236,7 @@ void MavlinkFtpClient::timeout() // In that case start requesting what we missed. if (item.current_offset == item.file_size && item.missing_data.empty()) { // We are done anyway. + item.ofstream.close(); item.callback(ClientResult::Success, {}); download_burst_end(*work); work_queue_guard.pop_front(); From 37c114590f2cde27184600b2de7c59e7a02cdfaf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 4 Apr 2024 19:57:05 +0200 Subject: [PATCH 03/15] core: add fs utils to get cache & temp directories --- src/mavsdk/core/CMakeLists.txt | 1 + src/mavsdk/core/fs_utils.cpp | 115 +++++++++++++++++++++++++++++++++ src/mavsdk/core/fs_utils.h | 20 ++++++ 3 files changed, 136 insertions(+) create mode 100644 src/mavsdk/core/fs_utils.cpp create mode 100644 src/mavsdk/core/fs_utils.h diff --git a/src/mavsdk/core/CMakeLists.txt b/src/mavsdk/core/CMakeLists.txt index 2baa885f37..cca74019ed 100644 --- a/src/mavsdk/core/CMakeLists.txt +++ b/src/mavsdk/core/CMakeLists.txt @@ -22,6 +22,7 @@ target_sources(mavsdk system.cpp system_impl.cpp flight_mode.cpp + fs_utils.cpp math_conversions.cpp mavsdk.cpp mavsdk_impl.cpp diff --git a/src/mavsdk/core/fs_utils.cpp b/src/mavsdk/core/fs_utils.cpp new file mode 100644 index 0000000000..e376cd4abe --- /dev/null +++ b/src/mavsdk/core/fs_utils.cpp @@ -0,0 +1,115 @@ + +#include "fs_utils.h" +#include "log.h" +#include +#include + +#if defined(LINUX) || defined(APPLE) +#include +#include +#include +#endif + +#ifdef WINDOWS +#include +#include +#endif + +namespace mavsdk { + +#ifdef WINDOWS +static std::optional get_known_windows_path(REFKNOWNFOLDERID folderId) +{ + std::filesystem::path path; + PWSTR path_tmp; + + /* Attempt to get user's AppData folder + * + * Microsoft Docs: + * https://learn.microsoft.com/en-us/windows/win32/api/shlobj_core/nf-shlobj_core-shgetknownfolderpath + * https://learn.microsoft.com/en-us/windows/win32/shell/knownfolderid + */ + auto get_folder_path_ret = SHGetKnownFolderPath(folderId, 0, nullptr, &path_tmp); + + /* Error check */ + if (get_folder_path_ret != S_OK) { + CoTaskMemFree(path_tmp); + return std::nullopt; + } + + /* Convert the Windows path type to a C++ path */ + path = path_tmp; + + CoTaskMemFree(path_tmp); + return path; +} +#endif + +std::optional get_cache_directory() +{ + // Windows: %LOCALAPPDATA% + // Android: /data/data//cache + // Linux: ~/.cache + // macOS: ~/Library/Caches +#if defined(WINDOWS) + auto path = get_known_windows_path(FOLDERID_LocalAppData); + if (path) { + return path->append("mavsdk_cache"); + } +#elif defined(ANDROID) + // Read /proc/self/cmdline + std::ifstream cmdline("/proc/self/cmdline"); + std::string line; + if (std::getline(cmdline, line)) { + // line might have a trailing \0 + if (line.length() > 0 && *line.end() == 0) { + line.pop_back(); + } + return "/data/data/" + line + "/mavsdk_cache"; + } +#elif defined(APPLE) || defined(LINUX) + const char* homedir; + if ((homedir = getenv("HOME")) == NULL) { + homedir = getpwuid(getuid())->pw_dir; + } + if (!homedir) { + return std::nullopt; + } +#if defined(APPLE) + return std::filesystem::path(homedir) / "Library" / "Caches" / "mavsdk"; +#else // Linux + return std::filesystem::path(homedir) / ".cache" / "mavsdk"; +#endif +#else +#error "Unsupported platform" +#endif + + return std::nullopt; +} + +std::optional create_tmp_directory(const std::string& prefix) +{ + // Inspired by https://stackoverflow.com/a/58454949/8548472 + const auto tmp_dir = std::filesystem::temp_directory_path(); + + std::random_device dev; + std::mt19937 prng(dev()); + std::uniform_int_distribution rand(0); + + static constexpr unsigned max_tries = 100; + + for (unsigned i = 0; i < max_tries; ++i) { + std::stringstream ss; + ss << prefix << '-' << std::hex << rand(prng); + auto path = tmp_dir / ss.str(); + + const auto created = std::filesystem::create_directory(path); + if (created) { + return path.string(); + } + } + + LogErr() << "Could not create a temporary directory, aborting."; + return std::nullopt; +} +} // namespace mavsdk diff --git a/src/mavsdk/core/fs_utils.h b/src/mavsdk/core/fs_utils.h new file mode 100644 index 0000000000..86bdb471e1 --- /dev/null +++ b/src/mavsdk/core/fs_utils.h @@ -0,0 +1,20 @@ +#pragma once + +#include +#include + +namespace mavsdk { + +/** + * Get the path to the system's cache directory with a MAVSDK-specific subdirectory. + * The path does not necessarily exist yet. + */ +std::optional get_cache_directory(); + +/** + * Create a random subdirectory in the system's tmp directory + * @param prefix directory prefix + */ +std::optional create_tmp_directory(const std::string& prefix); + +} // namespace mavsdk From b06c3f5cd63b9316d71aba9c5d98cf7cc6d916d3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 4 Apr 2024 16:26:50 +0200 Subject: [PATCH 04/15] component_metadata: add file cache class --- .../plugins/component_metadata/file_cache.cpp | 244 ++++++++++++++++++ .../plugins/component_metadata/file_cache.h | 89 +++++++ .../component_metadata/file_cache_test.cpp | 151 +++++++++++ 3 files changed, 484 insertions(+) create mode 100644 src/mavsdk/plugins/component_metadata/file_cache.cpp create mode 100644 src/mavsdk/plugins/component_metadata/file_cache.h create mode 100644 src/mavsdk/plugins/component_metadata/file_cache_test.cpp diff --git a/src/mavsdk/plugins/component_metadata/file_cache.cpp b/src/mavsdk/plugins/component_metadata/file_cache.cpp new file mode 100644 index 0000000000..af90dada1d --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/file_cache.cpp @@ -0,0 +1,244 @@ + +#include "file_cache.h" +#include "log.h" + +#include +#include + +// For directory locking +#ifdef WINDOWS +#include +#else +#include +#include +#include +#include +#endif + +namespace mavsdk { + +FileCache::DirectoryLock::DirectoryLock(const std::filesystem::path& path) : _path(path) +{ +#ifdef WINDOWS + _lock = + CreateFileA(_path.string().c_str(), GENERIC_READ, FILE_SHARE_READ, 0, OPEN_EXISTING, 0, 0); + if (!LockFileEx(_lock, LOCKFILE_EXCLUSIVE_LOCK, 0, _lock_size, 0, &_overlapped)) { + LogErr() << "Cannot take lock file " << GetLastError(); + } +#else + mode_t m = umask(0); + _fd = open(_path.c_str(), O_RDWR | O_CREAT, 0666); + umask(m); + if (_fd < 0) { + LogErr() << "Cannot open file " << _path; + } else { + if (flock(_fd, LOCK_EX) == -1) { + LogErr() << "Cannot lock file " << strerror(errno); + } + } +#endif +} +FileCache::DirectoryLock::~DirectoryLock() +{ +#ifdef WINDOWS + if (_lock != INVALID_HANDLE_VALUE) { + UnlockFileEx(_lock, 0, _lock_size, 0, &_overlapped); + CloseHandle(_lock); + } +#else + if (_fd >= 0) { + flock(_fd, LOCK_UN); + close(_fd); + } +#endif +} + +FileCache::FileCache(std::filesystem::path path, int max_num_files, bool verbose_debugging) : + _path(std::move(path)), + _max_num_files(max_num_files), + _verbose_debugging(verbose_debugging) +{ + if (!std::filesystem::exists(_path)) { + std::error_code err; + if (!std::filesystem::create_directories(_path, err)) { + LogErr() << "Failed to create cache directory: " << err.message(); + } + } +} + +std::filesystem::path FileCache::meta_filename(const std::string& file_tag) const +{ + return _path / (file_tag + _meta_extension); +} + +std::filesystem::path FileCache::data_filename(const std::string& file_tag) const +{ + return _path / (file_tag + _cache_extension); +} + +std::optional FileCache::access(const std::string& file_tag) +{ + const DirectoryLock directory_lock(_path / _lock_file); // also serves as multi-threadding lock + + const std::filesystem::path meta(meta_filename(file_tag)); + std::filesystem::path data(data_filename(file_tag)); + if (!std::filesystem::exists(meta) || !std::filesystem::exists(data)) { + if (_verbose_debugging) { + LogDebug() << "Cache miss for " << file_tag; + } + return std::nullopt; + } + + const auto access_counters = load_access_counters(); + remove_old_entries(access_counters); // Only needed if the cache size got reduced + // Check if entry is still valid (it could have been removed if the metadata is invalid) + if (!std::filesystem::exists(data)) { + if (_verbose_debugging) { + LogDebug() << "Cache miss for " << file_tag; + } + return std::nullopt; + } + + if (_verbose_debugging) { + LogDebug() << "Cache hit for " << file_tag; + } + + // Mark access + Meta m{}; + std::fstream meta_file(meta, std::ios::binary | std::ios::in | std::ios::out); + if (meta_file.good()) { + if (meta_file.read(reinterpret_cast(&m), sizeof(m)) && + meta_file.gcount() == sizeof(m)) { + m.access_counter = access_counters.next_access_counter; + meta_file.seekg(0); + if (!meta_file.write(reinterpret_cast(&m), sizeof(m))) { + LogErr() << "Meta write failed " << meta; + } + } else { + LogErr() << "Meta read failed " << meta; + } + } else { + LogErr() << "Failed to open " << meta; + } + + return data; +} + +std::optional +FileCache::insert(const std::string& file_tag, const std::filesystem::path& file_name) +{ + const DirectoryLock directory_lock(_path / _lock_file); // also serves as multi-threadding lock + + const std::filesystem::path meta(meta_filename(file_tag)); + std::filesystem::path data(data_filename(file_tag)); + auto access_counters = load_access_counters(); + + if (std::filesystem::exists(meta) && std::filesystem::exists(data)) { + if (_verbose_debugging) { + LogDebug() << "Not inserting, entry already exists: " << file_tag; + } + std::filesystem::remove(file_name); + return data; + } + + // Move the file to the cache location + std::error_code err; + std::filesystem::rename(file_name, data, err); + if (err) { + if (err.value() == EXDEV) { // different file system + std::filesystem::copy_file(file_name, data, err); + if (!err) { + std::filesystem::remove(file_name, err); + } + } + if (err) { + LogWarn() << "File rename failed from " << file_name << " to " << data << ": " + << err.message(); + return std::nullopt; + } + } + + // Write meta data + Meta m{}; + m.access_counter = access_counters.next_access_counter++; + std::fstream meta_file(meta, std::ios::binary | std::ios::out | std::ios::trunc); + if (meta_file.good()) { + if (!meta_file.write(reinterpret_cast(&m), sizeof(m))) { + LogWarn() << "Meta write failed " << meta; + } + access_counters.cached_files[m.access_counter] = file_tag; + } else { + LogWarn() << "Failed to open " << meta; + } + + remove_old_entries(access_counters); + return data; +} + +FileCache::AccessCounters FileCache::load_access_counters() const +{ + AccessCounters access_counters; + + for (const auto& path : std::filesystem::directory_iterator(_path)) { + if (path.path().extension() != _meta_extension) { + continue; + } + + bool validation_failed = false; + std::filesystem::path data(path); + data.replace_extension(_cache_extension); + if (!std::filesystem::exists(data)) { + validation_failed = true; + } + + // Read meta + validate + Meta m{}; + const uint32_t expected_magic = m.magic; + const uint32_t expected_version = m.version; + std::ifstream meta_file(path.path(), std::ios::binary); + if (meta_file.read(reinterpret_cast(&m), sizeof(m)) && + meta_file.gcount() == sizeof(m)) { + if (m.magic != expected_magic || m.version != expected_version) { + validation_failed = true; + } + } else { + validation_failed = true; + } + + if (validation_failed) { + LogWarn() << "Validation failed, removing cache files " << path.path(); + std::filesystem::remove(path.path()); + std::filesystem::remove(data); + } else { + // Extract the tag + const std::string tag = path.path().stem().string(); + access_counters.cached_files[m.access_counter] = tag; + + // LogDebug() << "Found cached file: " << path.path() << " counter: " << + // m.access_counter; + + if (m.access_counter >= access_counters.next_access_counter) { + access_counters.next_access_counter = m.access_counter + 1; + } + } + } + return access_counters; +} + +void FileCache::remove_old_entries(const AccessCounters& access_counters) const +{ + int num_delete = static_cast(access_counters.cached_files.size()) - _max_num_files; + auto iter = access_counters.cached_files.begin(); + while (num_delete > 0) { + if (_verbose_debugging) { + LogDebug() << "Removing cache entry num:counter:file" << num_delete << iter->first + << iter->second; + } + std::filesystem::remove(meta_filename(iter->second)); + std::filesystem::remove(data_filename(iter->second)); + --num_delete; + ++iter; + } +} + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_metadata/file_cache.h b/src/mavsdk/plugins/component_metadata/file_cache.h new file mode 100644 index 0000000000..8bc0fedc7c --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/file_cache.h @@ -0,0 +1,89 @@ +#pragma once + +#include +#include +#include +#include +#include + +#ifdef WINDOWS +#include +#endif + +namespace mavsdk { + +/** + * Simple file cache with a maximum number of files and LRU retention policy based on last access + * Notes: + * - fileTag defines the cache keys and the format is up to the user + * - thread-safe + * - multiple instances (or processes) can work on the same directory. + * (however there is no lock held when returning a file from a cache, so the assumption is that + * the cache is large enough so no other process evicts the file until it is used). + */ +class FileCache { +public: + FileCache(std::filesystem::path path, int max_num_files, bool verbose_debugging = false); + + /** + * Try to access a file and set the access counter + * @param fileTag + * @return file path or nullopt if not found + */ + std::optional access(const std::string& file_tag); + + /** + * Insert a file into the cache & remove old files if there's too many. + * @param fileTag + * @param fileName file to insert, will be moved (or deleted if already exists) + * @return cached file name if inserted or already exists, nullopt on error + */ + std::optional + insert(const std::string& file_tag, const std::filesystem::path& file_name); + +private: + class DirectoryLock { + public: + explicit DirectoryLock(const std::filesystem::path& path); + ~DirectoryLock(); + + private: +#ifdef WINDOWS + OVERLAPPED _overlapped{}; + const int _lock_size = 10000; + HANDLE _lock{}; +#else + int _fd{-1}; +#endif + const std::filesystem::path _path; + }; + + static constexpr const char* _meta_extension = ".meta"; + static constexpr const char* _cache_extension = ".cache"; + static constexpr const char* _lock_file = "lock"; + + using AccessCounterType = uint64_t; + + struct Meta { + uint32_t magic{0x9a9cad0e}; + uint32_t version{0}; + AccessCounterType access_counter{0}; + }; + + struct AccessCounters { + AccessCounterType next_access_counter{0}; + std::map cached_files; + }; + + AccessCounters load_access_counters() const; + void remove_old_entries(const AccessCounters& access_counters) const; + + std::filesystem::path meta_filename(const std::string& file_tag) const; + std::filesystem::path data_filename(const std::string& file_tag) const; + + const std::filesystem::path _path; + const int _max_num_files; + const bool _verbose_debugging; +}; + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_metadata/file_cache_test.cpp b/src/mavsdk/plugins/component_metadata/file_cache_test.cpp new file mode 100644 index 0000000000..1b73df11d0 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/file_cache_test.cpp @@ -0,0 +1,151 @@ + +#include +#include +#include "file_cache.h" +#include "fs_utils.h" + +using namespace mavsdk; + +class FileCacheTest : public testing::Test { +protected: + void SetUp() override + { + _cache_dir = get_cache_directory().value() / "mavsdk-test-file-cache"; + _tmp_files_dir = create_tmp_directory("mavsdk-test-file-cache").value(); + + cleanup(); + + std::filesystem::create_directories(_tmp_files_dir); + + for (int i = 0; i < 30; ++i) { + TmpFile t; + t.content = std::to_string(i); + t.path = _tmp_files_dir / (t.content + ".txt"); + char buf[100]; + snprintf(buf, sizeof(buf), "_tag_%08i_xy", i); + t.cache_tag = buf; + std::ofstream f(t.path, std::ios::out | std::ios::binary); + f.write(t.content.c_str(), t.content.length()); + f.close(); + _tmp_files.push_back(t); + } + } + + void TearDown() override { cleanup(); } + + void cleanup() + { + std::error_code ec; + std::filesystem::remove_all(_tmp_files_dir, ec); + std::filesystem::remove_all(_cache_dir, ec); + } + + struct TmpFile { + std::filesystem::path path; + std::string cache_tag; + std::string content; + std::filesystem::path cached_path; + }; + + std::vector _tmp_files; + + std::filesystem::path _cache_dir; + std::filesystem::path _tmp_files_dir; +}; + +TEST_F(FileCacheTest, basic_test) +{ + FileCache cache(_cache_dir, 10, true); + + ASSERT_TRUE(std::filesystem::is_directory(_cache_dir)); + + _tmp_files[0].cached_path = cache.insert(_tmp_files[0].cache_tag, _tmp_files[0].path).value(); + EXPECT_TRUE(std::filesystem::exists(_tmp_files[0].cached_path)); + EXPECT_FALSE(std::filesystem::exists(_tmp_files[0].path)); + + EXPECT_EQ(cache.access(_tmp_files[0].cache_tag).value(), _tmp_files[0].cached_path); + + std::ifstream f(_tmp_files[0].cached_path); + EXPECT_TRUE(f.good()); + std::stringstream buffer; + buffer << f.rdbuf(); + EXPECT_EQ(buffer.str(), _tmp_files[0].content); +} + +TEST_F(FileCacheTest, lru_test) +{ + FileCache cache(_cache_dir, 3, true); + + auto insert = [&](int idx) { + auto cached_path_option = cache.insert(_tmp_files[idx].cache_tag, _tmp_files[idx].path); + ASSERT_TRUE(cached_path_option); + _tmp_files[idx].cached_path = cached_path_option.value(); + }; + insert(1); + insert(3); + insert(0); + + EXPECT_EQ(cache.access(_tmp_files[0].cache_tag).value(), _tmp_files[0].cached_path); + EXPECT_EQ(cache.access(_tmp_files[1].cache_tag).value(), _tmp_files[1].cached_path); + EXPECT_EQ(cache.access(_tmp_files[3].cache_tag).value(), _tmp_files[3].cached_path); + + insert(4); + + EXPECT_FALSE(cache.access(_tmp_files[0].cache_tag)); + EXPECT_EQ(cache.access(_tmp_files[1].cache_tag).value(), _tmp_files[1].cached_path); + EXPECT_EQ(cache.access(_tmp_files[3].cache_tag).value(), _tmp_files[3].cached_path); + EXPECT_EQ(cache.access(_tmp_files[4].cache_tag).value(), _tmp_files[4].cached_path); + + EXPECT_EQ(cache.access(_tmp_files[3].cache_tag).value(), _tmp_files[3].cached_path); + EXPECT_EQ(cache.access(_tmp_files[1].cache_tag).value(), _tmp_files[1].cached_path); + EXPECT_EQ(cache.access(_tmp_files[3].cache_tag).value(), _tmp_files[3].cached_path); + + insert(5); + + EXPECT_FALSE(cache.access(_tmp_files[4].cache_tag)); + EXPECT_EQ(cache.access(_tmp_files[1].cache_tag).value(), _tmp_files[1].cached_path); + EXPECT_EQ(cache.access(_tmp_files[3].cache_tag).value(), _tmp_files[3].cached_path); + EXPECT_EQ(cache.access(_tmp_files[5].cache_tag).value(), _tmp_files[5].cached_path); + + EXPECT_EQ(cache.access(_tmp_files[3].cache_tag).value(), _tmp_files[3].cached_path); + insert(6); + insert(7); + + EXPECT_FALSE(cache.access(_tmp_files[4].cache_tag)); + EXPECT_FALSE(cache.access(_tmp_files[1].cache_tag)); + EXPECT_FALSE(cache.access(_tmp_files[5].cache_tag)); + EXPECT_EQ(cache.access(_tmp_files[3].cache_tag).value(), _tmp_files[3].cached_path); + EXPECT_EQ(cache.access(_tmp_files[6].cache_tag).value(), _tmp_files[6].cached_path); + EXPECT_EQ(cache.access(_tmp_files[7].cache_tag).value(), _tmp_files[7].cached_path); +} + +TEST_F(FileCacheTest, multi_test) +{ + auto insert = [&](FileCache& cache, int idx) { + auto cached_path_option = cache.insert(_tmp_files[idx].cache_tag, _tmp_files[idx].path); + ASSERT_TRUE(cached_path_option); + _tmp_files[idx].cached_path = cached_path_option.value(); + }; + + { + FileCache cache(_cache_dir, 5, true); + for (int i = 0; i < 5; ++i) { + insert(cache, i); + EXPECT_EQ(cache.access(_tmp_files[i].cache_tag).value(), _tmp_files[i].cached_path); + } + EXPECT_EQ(cache.access(_tmp_files[1].cache_tag).value(), _tmp_files[1].cached_path); + } + { + // reduce cache size and ensure oldest entries are evicted + FileCache cache(_cache_dir, 3, true); + EXPECT_FALSE(cache.access(_tmp_files[0].cache_tag)); + EXPECT_EQ(cache.access(_tmp_files[1].cache_tag).value(), _tmp_files[1].cached_path); + EXPECT_FALSE(cache.access(_tmp_files[2].cache_tag)); + EXPECT_EQ(cache.access(_tmp_files[3].cache_tag).value(), _tmp_files[3].cached_path); + EXPECT_EQ(cache.access(_tmp_files[4].cache_tag).value(), _tmp_files[4].cached_path); + + insert(cache, 10); + EXPECT_FALSE(cache.access(_tmp_files[1].cache_tag)); + EXPECT_EQ(cache.access(_tmp_files[10].cache_tag).value(), _tmp_files[10].cached_path); + } +} From 1222df7a7ec7afc2bd15bab97cff5276c29e428a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 4 Apr 2024 19:58:47 +0200 Subject: [PATCH 05/15] core: add MAV_COMP_ID_ONBOARD_COMPUTER to component_name --- src/mavsdk/core/system_impl.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/mavsdk/core/system_impl.cpp b/src/mavsdk/core/system_impl.cpp index f06392e804..e923d164a8 100644 --- a/src/mavsdk/core/system_impl.cpp +++ b/src/mavsdk/core/system_impl.cpp @@ -345,6 +345,8 @@ std::string SystemImpl::component_name(uint8_t component_id) return "Gimbal"; case MAV_COMP_ID_MISSIONPLANNER: return "Ground station"; + case MAV_COMP_ID_ONBOARD_COMPUTER: + return "Companion Computer"; case MAV_COMP_ID_WINCH: return "Winch"; default: From 150c6707f5f12bf158d089ef669a196e3e24bd8a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 11 Apr 2024 18:02:24 +0200 Subject: [PATCH 06/15] core: add liblzma dependency This version (5.4.5) is not affected by the recently discovered backdoor (https://tukaani.org/xz-backdoor/) --- src/CMakeLists.txt | 1 + src/mavsdk/core/CMakeLists.txt | 6 + src/mavsdk/core/inflate_lzma.cpp | 267 +++++++++++++++++++++++++++++ src/mavsdk/core/inflate_lzma.h | 14 ++ third_party/CMakeLists.txt | 1 + third_party/liblzma/CMakeLists.txt | 36 ++++ 6 files changed, 325 insertions(+) create mode 100644 src/mavsdk/core/inflate_lzma.cpp create mode 100644 src/mavsdk/core/inflate_lzma.h create mode 100644 third_party/liblzma/CMakeLists.txt diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 453f2df6e1..c4e39f826c 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -40,6 +40,7 @@ hunter_add_package(jsoncpp) hunter_add_package(CURL) find_package(CURL REQUIRED) +find_package(LibLZMA REQUIRED) if(BUILD_TESTS AND (IOS OR ANDROID)) message(STATUS "Building for iOS or Android: forcing BUILD_TESTS to FALSE...") diff --git a/src/mavsdk/core/CMakeLists.txt b/src/mavsdk/core/CMakeLists.txt index cca74019ed..57f494c0bf 100644 --- a/src/mavsdk/core/CMakeLists.txt +++ b/src/mavsdk/core/CMakeLists.txt @@ -23,6 +23,7 @@ target_sources(mavsdk system_impl.cpp flight_mode.cpp fs_utils.cpp + inflate_lzma.cpp math_conversions.cpp mavsdk.cpp mavsdk_impl.cpp @@ -64,6 +65,11 @@ cmake_policy(SET CMP0079 NEW) target_link_libraries(mavsdk PRIVATE Threads::Threads + ${LIBLZMA_LIBRARIES} +) +target_include_directories(mavsdk + PRIVATE + ${LIBLZMA_INCLUDE_DIRS} ) if (NOT BUILD_WITHOUT_CURL) diff --git a/src/mavsdk/core/inflate_lzma.cpp b/src/mavsdk/core/inflate_lzma.cpp new file mode 100644 index 0000000000..2c147465ef --- /dev/null +++ b/src/mavsdk/core/inflate_lzma.cpp @@ -0,0 +1,267 @@ + +#include "inflate_lzma.h" + +#include +#include +#include +#define LZMA_API_STATIC +#include + +// The following code is from the liblzma example: +// https://github.com/tukaani-project/xz/blob/master/doc/examples/02_decompress.c +static bool init_decoder(lzma_stream* strm) +{ + // Initialize a .xz decoder. The decoder supports a memory usage limit + // and a set of flags. + // + // The memory usage of the decompressor depends on the settings used + // to compress a .xz file. It can vary from less than a megabyte to + // a few gigabytes, but in practice (at least for now) it rarely + // exceeds 65 MiB because that's how much memory is required to + // decompress files created with "xz -9". Settings requiring more + // memory take extra effort to use and don't (at least for now) + // provide significantly better compression in most cases. + // + // Memory usage limit is useful if it is important that the + // decompressor won't consume gigabytes of memory. The need + // for limiting depends on the application. In this example, + // no memory usage limiting is used. This is done by setting + // the limit to UINT64_MAX. + // + // The .xz format allows concatenating compressed files as is: + // + // echo foo | xz > foobar.xz + // echo bar | xz >> foobar.xz + // + // When decompressing normal standalone .xz files, LZMA_CONCATENATED + // should always be used to support decompression of concatenated + // .xz files. If LZMA_CONCATENATED isn't used, the decoder will stop + // after the first .xz stream. This can be useful when .xz data has + // been embedded inside another file format. + // + // Flags other than LZMA_CONCATENATED are supported too, and can + // be combined with bitwise-or. See lzma/container.h + // (src/liblzma/api/lzma/container.h in the source package or e.g. + // /usr/include/lzma/container.h depending on the install prefix) + // for details. + lzma_ret ret = lzma_stream_decoder(strm, UINT64_MAX, LZMA_CONCATENATED); + + // Return successfully if the initialization went fine. + if (ret == LZMA_OK) + return true; + + // Something went wrong. The possible errors are documented in + // lzma/container.h (src/liblzma/api/lzma/container.h in the source + // package or e.g. /usr/include/lzma/container.h depending on the + // install prefix). + // + // Note that LZMA_MEMLIMIT_ERROR is never possible here. If you + // specify a very tiny limit, the error will be delayed until + // the first headers have been parsed by a call to lzma_code(). + const char* msg; + switch (ret) { + case LZMA_MEM_ERROR: + msg = "Memory allocation failed"; + break; + + case LZMA_OPTIONS_ERROR: + msg = "Unsupported decompressor flags"; + break; + + default: + // This is most likely LZMA_PROG_ERROR indicating a bug in + // this program or in liblzma. It is inconvenient to have a + // separate error message for errors that should be impossible + // to occur, but knowing the error code is important for + // debugging. That's why it is good to print the error code + // at least when there is no good error message to show. + msg = "Unknown error, possibly a bug"; + break; + } + + fprintf(stderr, "Error initializing the decoder: %s (error code %u)\n", msg, ret); + return false; +} + +static bool decompress(lzma_stream* strm, const char* inname, FILE* infile, FILE* outfile) +{ + // When LZMA_CONCATENATED flag was used when initializing the decoder, + // we need to tell lzma_code() when there will be no more input. + // This is done by setting action to LZMA_FINISH instead of LZMA_RUN + // in the same way as it is done when encoding. + // + // When LZMA_CONCATENATED isn't used, there is no need to use + // LZMA_FINISH to tell when all the input has been read, but it + // is still OK to use it if you want. When LZMA_CONCATENATED isn't + // used, the decoder will stop after the first .xz stream. In that + // case some unused data may be left in strm->next_in. + lzma_action action = LZMA_RUN; + + uint8_t inbuf[BUFSIZ]; + uint8_t outbuf[BUFSIZ]; + + strm->next_in = nullptr; + strm->avail_in = 0; + strm->next_out = outbuf; + strm->avail_out = sizeof(outbuf); + + while (true) { + if (strm->avail_in == 0 && !feof(infile)) { + strm->next_in = inbuf; + strm->avail_in = fread(inbuf, 1, sizeof(inbuf), infile); + + if (ferror(infile)) { + fprintf(stderr, "%s: Read error: %s\n", inname, strerror(errno)); + return false; + } + + // Once the end of the input file has been reached, + // we need to tell lzma_code() that no more input + // will be coming. As said before, this isn't required + // if the LZMA_CONCATENATED flag isn't used when + // initializing the decoder. + if (feof(infile)) + action = LZMA_FINISH; + } + + lzma_ret ret = lzma_code(strm, action); + + if (strm->avail_out == 0 || ret == LZMA_STREAM_END) { + size_t write_size = sizeof(outbuf) - strm->avail_out; + + if (fwrite(outbuf, 1, write_size, outfile) != write_size) { + fprintf(stderr, "Write error: %s\n", strerror(errno)); + return false; + } + + strm->next_out = outbuf; + strm->avail_out = sizeof(outbuf); + } + + if (ret != LZMA_OK) { + // Once everything has been decoded successfully, the + // return value of lzma_code() will be LZMA_STREAM_END. + // + // It is important to check for LZMA_STREAM_END. Do not + // assume that getting ret != LZMA_OK would mean that + // everything has gone well or that when you aren't + // getting more output it must have successfully + // decoded everything. + if (ret == LZMA_STREAM_END) + return true; + + // It's not LZMA_OK nor LZMA_STREAM_END, + // so it must be an error code. See lzma/base.h + // (src/liblzma/api/lzma/base.h in the source package + // or e.g. /usr/include/lzma/base.h depending on the + // install prefix) for the list and documentation of + // possible values. Many values listen in lzma_ret + // enumeration aren't possible in this example, but + // can be made possible by enabling memory usage limit + // or adding flags to the decoder initialization. + const char* msg; + switch (ret) { + case LZMA_MEM_ERROR: + msg = "Memory allocation failed"; + break; + + case LZMA_FORMAT_ERROR: + // .xz magic bytes weren't found. + msg = "The input is not in the .xz format"; + break; + + case LZMA_OPTIONS_ERROR: + // For example, the headers specify a filter + // that isn't supported by this liblzma + // version (or it hasn't been enabled when + // building liblzma, but no-one sane does + // that unless building liblzma for an + // embedded system). Upgrading to a newer + // liblzma might help. + // + // Note that it is unlikely that the file has + // accidentally became corrupt if you get this + // error. The integrity of the .xz headers is + // always verified with a CRC32, so + // unintentionally corrupt files can be + // distinguished from unsupported files. + msg = "Unsupported compression options"; + break; + + case LZMA_DATA_ERROR: + msg = "Compressed file is corrupt"; + break; + + case LZMA_BUF_ERROR: + // Typically this error means that a valid + // file has got truncated, but it might also + // be a damaged part in the file that makes + // the decoder think the file is truncated. + // If you prefer, you can use the same error + // message for this as for LZMA_DATA_ERROR. + msg = "Compressed file is truncated or " + "otherwise corrupt"; + break; + + default: + // This is most likely LZMA_PROG_ERROR. + msg = "Unknown error, possibly a bug"; + break; + } + + fprintf( + stderr, + "%s: Decoder error: " + "%s (error code %u)\n", + inname, + msg, + ret); + return false; + } + } +} + +bool InflateLZMA::inflateLZMAFile( + const std::filesystem::path& lzma_filename, const std::filesystem::path& decompressed_filename) +{ + lzma_stream strm = LZMA_STREAM_INIT; + + if (!init_decoder(&strm)) { + // Decoder initialization failed. There's no point + // to retry it so we need to exit. + return false; + } + + FILE* infile = fopen(lzma_filename.string().c_str(), "rb"); + + if (infile == nullptr) { + fprintf( + stderr, + "%s: Error opening the " + "input file: %s\n", + lzma_filename.string().c_str(), + strerror(errno)); + return false; + } + + FILE* outfile = fopen(decompressed_filename.string().c_str(), "wb"); + + if (outfile == nullptr) { + fprintf( + stderr, + "%s: Error opening the " + "output file: %s\n", + decompressed_filename.string().c_str(), + strerror(errno)); + fclose(infile); + return false; + } + + const bool success = decompress(&strm, lzma_filename.string().c_str(), infile, outfile); + fclose(infile); + fclose(outfile); + + lzma_end(&strm); + + return success; +} \ No newline at end of file diff --git a/src/mavsdk/core/inflate_lzma.h b/src/mavsdk/core/inflate_lzma.h new file mode 100644 index 0000000000..9df8396fe7 --- /dev/null +++ b/src/mavsdk/core/inflate_lzma.h @@ -0,0 +1,14 @@ + +#pragma once + +#include + +class InflateLZMA { +public: + /// Decompresses the specified file to the specified directory + /// @param lzma_filename Fully qualified path to lzma file + /// @param decompressed_filename Fully qualified path to for file to decompress to + static bool inflateLZMAFile( + const std::filesystem::path& lzma_filename, + const std::filesystem::path& decompressed_filename); +}; diff --git a/third_party/CMakeLists.txt b/third_party/CMakeLists.txt index a38a2b391f..75ae778172 100644 --- a/third_party/CMakeLists.txt +++ b/third_party/CMakeLists.txt @@ -11,6 +11,7 @@ if (SUPERBUILD) build_target(mavlink) build_target(jsoncpp) build_target(tinyxml2) + build_target(liblzma) if(NOT BUILD_WITHOUT_CURL) if(NOT IOS) diff --git a/third_party/liblzma/CMakeLists.txt b/third_party/liblzma/CMakeLists.txt new file mode 100644 index 0000000000..f3a10a9f67 --- /dev/null +++ b/third_party/liblzma/CMakeLists.txt @@ -0,0 +1,36 @@ +cmake_minimum_required(VERSION 3.1) + +project(external-liblzma) +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}" + ) + +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 \"liblzma\" with args:") +foreach(CMAKE_ARG ${CMAKE_ARGS}) + message(STATUS "-- ${CMAKE_ARG}") +endforeach() + +ExternalProject_Add( + liblzma + URL https://github.com/tukaani-project/xz/releases/download/v5.4.5/xz-5.4.5.tar.gz + URL_MD5 d2bb81e1a1a7808352c4ca28622f5c72 + CMAKE_ARGS "${CMAKE_ARGS}" +) \ No newline at end of file From 6fb125721cdb30e77eb78ff1148a9081d8ec4e37 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 4 Apr 2024 20:00:51 +0200 Subject: [PATCH 07/15] component_metadata: add protocol implementation --- .../component_information/CMakeLists.txt | 15 - .../component_information.cpp | 111 --- .../component_information_impl.cpp | 298 -------- .../component_information_impl.h | 53 -- .../component_information.h | 183 ----- .../plugins/component_metadata/CMakeLists.txt | 22 + .../component_metadata/component_metadata.cpp | 36 + .../component_metadata_impl.cpp | 651 ++++++++++++++++++ .../component_metadata_impl.h | 154 +++++ .../component_metadata_test.cpp | 32 + .../component_metadata/component_metadata.h | 95 +++ src/plugins.txt | 2 +- 12 files changed, 991 insertions(+), 661 deletions(-) delete mode 100644 src/mavsdk/plugins/component_information/CMakeLists.txt delete mode 100644 src/mavsdk/plugins/component_information/component_information.cpp delete mode 100644 src/mavsdk/plugins/component_information/component_information_impl.cpp delete mode 100644 src/mavsdk/plugins/component_information/component_information_impl.h delete mode 100644 src/mavsdk/plugins/component_information/include/plugins/component_information/component_information.h create mode 100644 src/mavsdk/plugins/component_metadata/CMakeLists.txt create mode 100644 src/mavsdk/plugins/component_metadata/component_metadata.cpp create mode 100644 src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp create mode 100644 src/mavsdk/plugins/component_metadata/component_metadata_impl.h create mode 100644 src/mavsdk/plugins/component_metadata/component_metadata_test.cpp create mode 100644 src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h diff --git a/src/mavsdk/plugins/component_information/CMakeLists.txt b/src/mavsdk/plugins/component_information/CMakeLists.txt deleted file mode 100644 index 93f76f067e..0000000000 --- a/src/mavsdk/plugins/component_information/CMakeLists.txt +++ /dev/null @@ -1,15 +0,0 @@ -target_sources(mavsdk - PRIVATE - component_information.cpp - component_information_impl.cpp -) - -target_include_directories(mavsdk PUBLIC - $ - $ - ) - -install(FILES - include/plugins/component_information/component_information.h - DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/mavsdk/plugins/component_information -) diff --git a/src/mavsdk/plugins/component_information/component_information.cpp b/src/mavsdk/plugins/component_information/component_information.cpp deleted file mode 100644 index 89a393af82..0000000000 --- a/src/mavsdk/plugins/component_information/component_information.cpp +++ /dev/null @@ -1,111 +0,0 @@ -// 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/component_information/component_information.proto) - -#include - -#include "component_information_impl.h" -#include "plugins/component_information/component_information.h" - -namespace mavsdk { - -using FloatParam = ComponentInformation::FloatParam; -using FloatParamUpdate = ComponentInformation::FloatParamUpdate; - -ComponentInformation::ComponentInformation(System& system) : - PluginBase(), - _impl{std::make_unique(system)} -{} - -ComponentInformation::ComponentInformation(std::shared_ptr system) : - PluginBase(), - _impl{std::make_unique(system)} -{} - -ComponentInformation::~ComponentInformation() {} - -std::pair> -ComponentInformation::access_float_params() const -{ - return _impl->access_float_params(); -} - -ComponentInformation::FloatParamHandle -ComponentInformation::subscribe_float_param(const FloatParamCallback& callback) -{ - return _impl->subscribe_float_param(callback); -} - -void ComponentInformation::unsubscribe_float_param(FloatParamHandle handle) -{ - _impl->unsubscribe_float_param(handle); -} - -bool operator==( - const ComponentInformation::FloatParam& lhs, const ComponentInformation::FloatParam& rhs) -{ - return (rhs.name == lhs.name) && (rhs.short_description == lhs.short_description) && - (rhs.long_description == lhs.long_description) && (rhs.unit == lhs.unit) && - (rhs.decimal_places == lhs.decimal_places) && - ((std::isnan(rhs.start_value) && std::isnan(lhs.start_value)) || - rhs.start_value == lhs.start_value) && - ((std::isnan(rhs.default_value) && std::isnan(lhs.default_value)) || - rhs.default_value == lhs.default_value) && - ((std::isnan(rhs.min_value) && std::isnan(lhs.min_value)) || - rhs.min_value == lhs.min_value) && - ((std::isnan(rhs.max_value) && std::isnan(lhs.max_value)) || - rhs.max_value == lhs.max_value); -} - -std::ostream& operator<<(std::ostream& str, ComponentInformation::FloatParam const& float_param) -{ - str << std::setprecision(15); - str << "float_param:" << '\n' << "{\n"; - str << " name: " << float_param.name << '\n'; - str << " short_description: " << float_param.short_description << '\n'; - str << " long_description: " << float_param.long_description << '\n'; - str << " unit: " << float_param.unit << '\n'; - str << " decimal_places: " << float_param.decimal_places << '\n'; - str << " start_value: " << float_param.start_value << '\n'; - str << " default_value: " << float_param.default_value << '\n'; - str << " min_value: " << float_param.min_value << '\n'; - str << " max_value: " << float_param.max_value << '\n'; - str << '}'; - return str; -} - -bool operator==( - const ComponentInformation::FloatParamUpdate& lhs, - const ComponentInformation::FloatParamUpdate& rhs) -{ - return (rhs.name == lhs.name) && - ((std::isnan(rhs.value) && std::isnan(lhs.value)) || rhs.value == lhs.value); -} - -std::ostream& -operator<<(std::ostream& str, ComponentInformation::FloatParamUpdate const& float_param_update) -{ - str << std::setprecision(15); - str << "float_param_update:" << '\n' << "{\n"; - str << " name: " << float_param_update.name << '\n'; - str << " value: " << float_param_update.value << '\n'; - str << '}'; - return str; -} - -std::ostream& operator<<(std::ostream& str, ComponentInformation::Result const& result) -{ - switch (result) { - case ComponentInformation::Result::Unknown: - return str << "Unknown"; - case ComponentInformation::Result::Success: - return str << "Success"; - case ComponentInformation::Result::NoSystem: - return str << "No System"; - default: - return str << "Unknown"; - } -} - -} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/component_information/component_information_impl.cpp b/src/mavsdk/plugins/component_information/component_information_impl.cpp deleted file mode 100644 index 673ad31501..0000000000 --- a/src/mavsdk/plugins/component_information/component_information_impl.cpp +++ /dev/null @@ -1,298 +0,0 @@ -#include "component_information_impl.h" -#include "callback_list.tpp" - -#include -#include -#include -#include -#include - -namespace mavsdk { - -namespace fs = std::filesystem; - -template class CallbackList; - -ComponentInformationImpl::ComponentInformationImpl(System& system) : PluginImplBase(system) -{ - _system_impl->register_plugin(this); -} - -ComponentInformationImpl::ComponentInformationImpl(std::shared_ptr system) : - PluginImplBase(std::move(system)) -{ - _system_impl->register_plugin(this); -} - -ComponentInformationImpl::~ComponentInformationImpl() -{ - _system_impl->unregister_plugin(this); -} - -void ComponentInformationImpl::init() {} - -void ComponentInformationImpl::deinit() {} - -void ComponentInformationImpl::enable() -{ - // TODO: iterate through components! - - _system_impl->request_message().request( - MAVLINK_MSG_ID_COMPONENT_INFORMATION, - MAV_COMP_ID_PATHPLANNER, - [this](auto&& result, auto&& message) { receive_component_information(result, message); }); -} - -void ComponentInformationImpl::disable() {} - -void ComponentInformationImpl::receive_component_information( - MavlinkCommandSender::Result result, const mavlink_message_t& message) -{ - if (result != MavlinkCommandSender::Result::Success) { - LogWarn() << "Requesting component information failed with " << static_cast(result); - return; - } - - mavlink_component_information_t component_information; - mavlink_msg_component_information_decode(&message, &component_information); - - component_information - .general_metadata_uri[sizeof(component_information.general_metadata_uri) - 1] = '\0'; - const auto general_metadata_uri = std::string(component_information.general_metadata_uri); - - download_file_async( - general_metadata_uri, [this](std::string path) { parse_metadata_file(path); }); -} - -void ComponentInformationImpl::download_file_async( - const std::string& uri, std::function callback) -{ - // TODO: check CRC - - if (uri.empty()) { - LogErr() << "No component information URI provided"; - return; - - } else if (uri.find("mftp://") == 0) { - LogDebug() << "Found mftp URI, using MAVLink FTP to download file"; - - const auto path = uri.substr(strlen("mftp://")); - - const auto maybe_tmp_path = create_tmp_directory("mavsdk-component-information-tmp-files"); - const auto path_to_download = maybe_tmp_path ? maybe_tmp_path.value() : "./"; - - _system_impl->mavlink_ftp_client().download_async( - path, - path_to_download, - false, // Don't use burst for now - [path_to_download, callback, path]( - MavlinkFtpClient::ClientResult download_result, - MavlinkFtpClient::ProgressData progress_data) { - if (download_result == MavlinkFtpClient::ClientResult::Next) { - LogDebug() << "File download progress: " << progress_data.bytes_transferred - << '/' << progress_data.total_bytes; - } else { - LogDebug() << "File download ended with result " << download_result; - if (download_result == MavlinkFtpClient::ClientResult::Success) { - LogDebug() << "Received file " << path_to_download + "/" + path; - callback(path_to_download + "/" + path); - } - } - }); - } else if (uri.find("http://") == 0 || uri.find("https://") == 0) { - LogWarn() << "Download using http(s) not implemented yet"; - } else { - LogWarn() << "Unknown URI protocol"; - } -} - -void ComponentInformationImpl::parse_metadata_file(const std::string& path) -{ - std::ifstream f(path); - if (f.bad()) { - LogErr() << "Could not open json metadata file."; - return; - } - - Json::Value metadata; - f >> metadata; - - if (!metadata.isMember("version")) { - LogErr() << "version not found"; - return; - } - - if (metadata["version"].asInt() != 1) { - LogWarn() << "version " << metadata["version"].asInt() << " not supported"; - } - - if (!metadata.isMember("metadataTypes")) { - LogErr() << "metadataTypes not found"; - return; - } - - for (auto& metadata_type : metadata["metadataTypes"]) { - if (!metadata_type.isMember("type")) { - LogErr() << "type missing"; - return; - } - if (!metadata_type.isMember("uri")) { - LogErr() << "uri missing"; - return; - } - - if (metadata_type["type"].asInt() == COMP_METADATA_TYPE_PARAMETER) { - download_file_async( - metadata_type["uri"].asString(), [this](const std::string& parameter_file_path) { - LogDebug() << "Found parameter file at: " << parameter_file_path; - parse_parameter_file(parameter_file_path); - }); - } - } -} - -void ComponentInformationImpl::parse_parameter_file(const std::string& path) -{ - std::ifstream f(path); - if (f.bad()) { - LogErr() << "Could not open json parameter file."; - return; - } - - Json::Value parameters; - f >> parameters; - - if (!parameters.isMember("version")) { - LogErr() << "version not found"; - return; - } - - if (parameters["version"].asInt() != 1) { - LogWarn() << "version " << parameters["version"].asInt() << " not supported"; - } - - if (!parameters.isMember("parameters")) { - LogErr() << "parameters not found"; - return; - } - - std::lock_guard lock(_mutex); - _float_params.clear(); - - for (auto& param : parameters["parameters"]) { - if (!param.isMember("type")) { - LogErr() << "type not found"; - return; - } - - if (param["type"].asString() == "Float") { - _float_params.push_back(ComponentInformation::FloatParam{ - param["name"].asString(), - param["shortDesc"].asString(), - param["longDesc"].asString(), - param["units"].asString(), - param["decimalPlaces"].asInt(), - NAN, - param["default"].asFloat(), - param["min"].asFloat(), - param["max"].asFloat()}); - - const auto name = param["name"].asString(); - - _system_impl->get_param_float_async( - name, - [this, name](MavlinkParameterClient::Result result, float value) { - get_float_param_result(name, result, value); - }, - this); - - _system_impl->subscribe_param_float( - name, [this, name](float value) { param_update(name, value); }, this); - - } else { - LogWarn() << "Ignoring type " << param["type"].asString() << " for now."; - } - } -} - -void ComponentInformationImpl::get_float_param_result( - const std::string& name, MavlinkParameterClient::Result result, float value) -{ - if (result != MavlinkParameterClient::Result::Success) { - LogWarn() << "Getting float param result: " << static_cast(result); - return; - } - - std::lock_guard lock(_mutex); - for (auto& param : _float_params) { - if (param.name == name) { - param.start_value = value; - LogDebug() << "Received value " << value << " for " << name; - } - } -} - -void ComponentInformationImpl::param_update(const std::string& name, float new_value) -{ - std::lock_guard lock(_mutex); - - for (auto& param : _float_params) { - if (param.name == name) { - param.start_value = new_value; - LogDebug() << "Received value " << new_value << " for " << name; - } - } - - const auto param_update = ComponentInformation::FloatParamUpdate{name, new_value}; - - _float_param_update_callbacks.queue( - param_update, [this](const auto& func) { _system_impl->call_user_callback(func); }); -} - -std::pair> -ComponentInformationImpl::access_float_params() -{ - return {ComponentInformation::Result::Success, _float_params}; -} - -ComponentInformation::FloatParamHandle ComponentInformationImpl::subscribe_float_param( - const ComponentInformation::FloatParamCallback& callback) -{ - std::lock_guard lock(_mutex); - return _float_param_update_callbacks.subscribe(callback); -} - -void ComponentInformationImpl::unsubscribe_float_param( - ComponentInformation::FloatParamHandle handle) -{ - std::lock_guard lock(_mutex); - _float_param_update_callbacks.unsubscribe(handle); -} - -std::optional ComponentInformationImpl::create_tmp_directory(const std::string& prefix) -{ - // Inspired by https://stackoverflow.com/a/58454949/8548472 - const auto tmp_dir = fs::temp_directory_path(); - - std::random_device dev; - std::mt19937 prng(dev()); - std::uniform_int_distribution rand(0); - - static constexpr unsigned max_tries = 100; - - for (unsigned i = 0; i < max_tries; ++i) { - std::stringstream ss; - ss << prefix << '-' << std::hex << rand(prng); - auto path = tmp_dir / ss.str(); - - const auto created = fs::create_directory(path); - if (created) { - return {path.string()}; - } - } - - LogErr() << "Could not create a temporary directory, aborting."; - return {}; -} - -} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_information/component_information_impl.h b/src/mavsdk/plugins/component_information/component_information_impl.h deleted file mode 100644 index 153a9aca90..0000000000 --- a/src/mavsdk/plugins/component_information/component_information_impl.h +++ /dev/null @@ -1,53 +0,0 @@ -#pragma once - -#include "plugins/component_information/component_information.h" -#include "plugin_impl_base.h" -#include "callback_list.h" - -#include -#include - -namespace mavsdk { - -class ComponentInformationImpl : public PluginImplBase { -public: - explicit ComponentInformationImpl(System& system); - explicit ComponentInformationImpl(std::shared_ptr system); - ~ComponentInformationImpl() override; - - void init() override; - void deinit() override; - - void enable() override; - void disable() override; - - std::pair> - access_float_params(); - - ComponentInformation::FloatParamHandle - subscribe_float_param(const ComponentInformation::FloatParamCallback& callback); - void unsubscribe_float_param(ComponentInformation::FloatParamHandle handle); - -private: - void receive_component_information( - MavlinkCommandSender::Result result, const mavlink_message_t& message); - - void - download_file_async(const std::string& uri, std::function callback); - void parse_metadata_file(const std::string& path); - void parse_parameter_file(const std::string& path); - - void get_float_param_result( - const std::string& name, MavlinkParameterClient::Result result, float value); - - void param_update(const std::string& name, float new_value); - - std::optional create_tmp_directory(const std::string& prefix); - - std::mutex _mutex{}; - std::vector _float_params{}; - - CallbackList _float_param_update_callbacks{}; -}; - -} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_information/include/plugins/component_information/component_information.h b/src/mavsdk/plugins/component_information/include/plugins/component_information/component_information.h deleted file mode 100644 index 27bbc01576..0000000000 --- a/src/mavsdk/plugins/component_information/include/plugins/component_information/component_information.h +++ /dev/null @@ -1,183 +0,0 @@ -// 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/component_information/component_information.proto) - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "plugin_base.h" - -#include "handle.h" - -namespace mavsdk { - -class System; -class ComponentInformationImpl; - -/** - * @brief Access component information such as parameters. - */ -class ComponentInformation : public PluginBase { -public: - /** - * @brief Constructor. Creates the plugin for a specific System. - * - * The plugin is typically created as shown below: - * - * ```cpp - * auto component_information = ComponentInformation(system); - * ``` - * - * @param system The specific system associated with this plugin. - */ - explicit ComponentInformation(System& system); // deprecated - - /** - * @brief Constructor. Creates the plugin for a specific System. - * - * The plugin is typically created as shown below: - * - * ```cpp - * auto component_information = ComponentInformation(system); - * ``` - * - * @param system The specific system associated with this plugin. - */ - explicit ComponentInformation(std::shared_ptr system); // new - - /** - * @brief Destructor (internal use only). - */ - ~ComponentInformation() override; - - /** - * @brief Meta information for parameter of type float. - */ - struct FloatParam { - std::string name{}; /**< @brief Name (max 16 chars) */ - std::string short_description{}; /**< @brief Short description */ - std::string long_description{}; /**< @brief Long description */ - std::string unit{}; /**< @brief Unit */ - int32_t decimal_places{}; /**< @brief Decimal places for user to show */ - float start_value{}; /**< @brief Current/starting value */ - float default_value{}; /**< @brief Default value */ - float min_value{}; /**< @brief Minimum value */ - float max_value{}; /**< @brief Maximum value */ - }; - - /** - * @brief Equal operator to compare two `ComponentInformation::FloatParam` objects. - * - * @return `true` if items are equal. - */ - friend bool operator==( - const ComponentInformation::FloatParam& lhs, const ComponentInformation::FloatParam& rhs); - - /** - * @brief Stream operator to print information about a `ComponentInformation::FloatParam`. - * - * @return A reference to the stream. - */ - friend std::ostream& - operator<<(std::ostream& str, ComponentInformation::FloatParam const& float_param); - - /** - * @brief A float param that has been updated. - */ - struct FloatParamUpdate { - std::string name{}; /**< @brief Name of param that changed */ - float value{}; /**< @brief New value of param */ - }; - - /** - * @brief Equal operator to compare two `ComponentInformation::FloatParamUpdate` objects. - * - * @return `true` if items are equal. - */ - friend bool operator==( - const ComponentInformation::FloatParamUpdate& lhs, - const ComponentInformation::FloatParamUpdate& rhs); - - /** - * @brief Stream operator to print information about a `ComponentInformation::FloatParamUpdate`. - * - * @return A reference to the stream. - */ - friend std::ostream& - operator<<(std::ostream& str, ComponentInformation::FloatParamUpdate const& float_param_update); - - /** - * @brief Possible results returned for param requests. - */ - enum class Result { - Unknown, /**< @brief Unknown result. */ - Success, /**< @brief Request succeeded. */ - NoSystem, /**< @brief No system is connected. */ - }; - - /** - * @brief Stream operator to print information about a `ComponentInformation::Result`. - * - * @return A reference to the stream. - */ - friend std::ostream& operator<<(std::ostream& str, ComponentInformation::Result const& result); - - /** - * @brief Callback type for asynchronous ComponentInformation calls. - */ - using ResultCallback = std::function; - - /** - * @brief List available float params. - * - * This function is blocking. - * - * @return Result of request. - */ - std::pair> access_float_params() const; - - /** - * @brief Callback type for subscribe_float_param. - */ - using FloatParamCallback = std::function; - - /** - * @brief Handle type for subscribe_float_param. - */ - using FloatParamHandle = Handle; - - /** - * @brief Subscribe to float param changes/updates. - */ - FloatParamHandle subscribe_float_param(const FloatParamCallback& callback); - - /** - * @brief Unsubscribe from subscribe_float_param - */ - void unsubscribe_float_param(FloatParamHandle handle); - - /** - * @brief Copy constructor. - */ - ComponentInformation(const ComponentInformation& other); - - /** - * @brief Equality operator (object is not copyable). - */ - const ComponentInformation& operator=(const ComponentInformation&) = 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/plugins/component_metadata/CMakeLists.txt b/src/mavsdk/plugins/component_metadata/CMakeLists.txt new file mode 100644 index 0000000000..58332fbf34 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/CMakeLists.txt @@ -0,0 +1,22 @@ +target_sources(mavsdk + PRIVATE + component_metadata.cpp + component_metadata_impl.cpp + file_cache.cpp +) + +target_include_directories(mavsdk PUBLIC + $ + $ + ) + +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.cpp b/src/mavsdk/plugins/component_metadata/component_metadata.cpp new file mode 100644 index 0000000000..9eac6a97d0 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/component_metadata.cpp @@ -0,0 +1,36 @@ +// 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/component_metadata/component_metadata.proto) + +#include + +#include "component_metadata_impl.h" +#include "plugins/component_metadata/component_metadata.h" + +namespace mavsdk { + +ComponentMetadata::ComponentMetadata(System& system, std::vector components_to_request) : + PluginBase(), + _impl{std::make_unique(system, std::move(components_to_request))} +{} + +ComponentMetadata::ComponentMetadata( + std::shared_ptr system, std::vector components_to_request) : + PluginBase(), + _impl{std::make_unique(system, std::move(components_to_request))} +{} + +ComponentMetadata::~ComponentMetadata() {} +std::pair +ComponentMetadata::get_metadata(ComponentMetadata::MetadataType type, uint32_t compid) +{ + return _impl->get_metadata(type, compid); +} +void ComponentMetadata::register_notification_callback( + const ComponentMetadata::NotificationCallback& callback) +{ + _impl->register_notification_callback(callback); +} + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp b/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp new file mode 100644 index 0000000000..09eb7886a4 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp @@ -0,0 +1,651 @@ +#include "component_metadata_impl.h" +#include "callback_list.tpp" +#include "fs_utils.h" +#include "inflate_lzma.h" + +#include +#include +#include +#include +#include + +#ifdef WINDOWS +#define strncasecmp(x, y, z) _strnicmp(x, y, z) +#endif + +namespace mavsdk { + +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() {} + +void ComponentMetadataImpl::deinit() {} + +void ComponentMetadataImpl::enable() +{ + const std::lock_guard lg{_mavlink_components_mutex}; + _mavlink_components.clear(); + 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}; + 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); + }); + } + } +} + +void ComponentMetadataImpl::request_component(uint32_t compid) +{ + _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) +{ + 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->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, Status status, CURLcode curl_code) -> int { + if (status == Status::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) { + 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 ComponentMetadataImpl::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( + 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); + } +} + +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) +{ + // 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) +{ + switch (type) { + case COMP_METADATA_TYPE_PARAMETER: + return ComponentMetadata::MetadataType::Parameter; + case COMP_METADATA_TYPE_EVENTS: + return ComponentMetadata::MetadataType::Events; + case COMP_METADATA_TYPE_ACTUATORS: + return ComponentMetadata::MetadataType::Actuators; + default: + break; + } + + return std::nullopt; +} +std::pair +ComponentMetadataImpl::get_metadata(uint32_t compid, ComponentMetadata::MetadataType type) +{ + COMP_METADATA_TYPE metadata_type{COMP_METADATA_TYPE_GENERAL}; + switch (type) { + case ComponentMetadata::MetadataType::Parameter: + metadata_type = COMP_METADATA_TYPE_PARAMETER; + break; + case ComponentMetadata::MetadataType::Events: + metadata_type = COMP_METADATA_TYPE_EVENTS; + break; + 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}}); + } +} +void ComponentMetadataImpl::unsubscribe_metadata_available( + ComponentMetadata::MetadataAvailableHandle handle) +{ + const std::lock_guard lg{_notification_callbacks_mutex}; + _notification_callbacks.unsubscribe(handle); +} +ComponentMetadata::MetadataAvailableHandle ComponentMetadataImpl::subscribe_metadata_available( + const ComponentMetadata::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(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(); + } +} + +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 new file mode 100644 index 0000000000..bb7d28277c --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/component_metadata_impl.h @@ -0,0 +1,154 @@ +#pragma once + +#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 +#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); + explicit ComponentMetadataImpl(std::shared_ptr system); + ~ComponentMetadataImpl() override; + + void init() override; + void deinit() override; + + void enable() override; + void disable() override; + + void request_component(uint32_t compid); + void request_autopilot_component() { request_component(MAV_COMP_ID_AUTOPILOT1); } + + std::pair + get_metadata(uint32_t compid, ComponentMetadata::MetadataType type); + + ComponentMetadata::MetadataAvailableHandle + 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); + + std::set _components_to_request; + bool _is_enabled{false}; + + 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/plugins/component_metadata/component_metadata_test.cpp b/src/mavsdk/plugins/component_metadata/component_metadata_test.cpp new file mode 100644 index 0000000000..bbebca2468 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/component_metadata_test.cpp @@ -0,0 +1,32 @@ +#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"); +} diff --git a/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h b/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h new file mode 100644 index 0000000000..4a5d038d08 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h @@ -0,0 +1,95 @@ +// 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/component_metadata/component_metadata.proto) + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "mavlink_include.h" +#include "plugin_base.h" + +#include "handle.h" + +namespace mavsdk { + +class System; +class ComponentMetadataImpl; + +/** + * @brief Access component metadata such as parameters. + */ +class ComponentMetadata : public PluginBase { +public: + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto component_metadata = ComponentMetadata(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit ComponentMetadata( + System& system, + std::vector components_to_request = {MAV_COMP_ID_AUTOPILOT1}); // deprecated + + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto component_metadata = ComponentMetadata(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit ComponentMetadata( + std::shared_ptr system, + std::vector components_to_request = {MAV_COMP_ID_AUTOPILOT1}); // new + + /** + * @brief Destructor (internal use only). + */ + ~ComponentMetadata() override; + + enum class MetadataType { + Parameter, + Events, + Actuators, + }; + + std::pair get_metadata(MetadataType type, uint32_t compid); + + using NotificationCallback = + std::function; + + void register_notification_callback(const NotificationCallback& callback); + + /** + * @brief Copy constructor. + */ + ComponentMetadata(const ComponentMetadata& other) = delete; + + /** + * @brief Equality operator (object is not copyable). + */ + const ComponentMetadata& operator=(const ComponentMetadata&) = delete; + +private: + /** @private Underlying implementation, set at instantiation */ + std::unique_ptr _impl; +}; + +} // namespace mavsdk \ No newline at end of file diff --git a/src/plugins.txt b/src/plugins.txt index 651b5613c9..3eed57c61f 100644 --- a/src/plugins.txt +++ b/src/plugins.txt @@ -4,7 +4,7 @@ arm_authorizer_server calibration camera camera_server -component_information +component_metadata component_information_server failure follow_me From 248acc0651d106815e9baf8abaf907c5e9b13375 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 4 Apr 2024 20:01:16 +0200 Subject: [PATCH 08/15] component_metadata: add server protocol implementation --- .../component_information_server.cpp | 117 ----------- .../component_information_server_impl.cpp | 189 ------------------ .../component_information_server_impl.h | 41 ---- .../component_information_server.h | 177 ---------------- .../CMakeLists.txt | 6 +- .../component_metadata_server.cpp | 23 +++ .../component_metadata_server_impl.cpp | 174 ++++++++++++++++ .../component_metadata_server_impl.h | 44 ++++ .../component_metadata_server.h | 77 +++++++ src/plugins.txt | 2 +- 10 files changed, 322 insertions(+), 528 deletions(-) delete mode 100644 src/mavsdk/plugins/component_information_server/component_information_server.cpp delete mode 100644 src/mavsdk/plugins/component_information_server/component_information_server_impl.cpp delete mode 100644 src/mavsdk/plugins/component_information_server/component_information_server_impl.h delete mode 100644 src/mavsdk/plugins/component_information_server/include/plugins/component_information_server/component_information_server.h rename src/mavsdk/plugins/{component_information_server => component_metadata_server}/CMakeLists.txt (64%) create mode 100644 src/mavsdk/plugins/component_metadata_server/component_metadata_server.cpp create mode 100644 src/mavsdk/plugins/component_metadata_server/component_metadata_server_impl.cpp create mode 100644 src/mavsdk/plugins/component_metadata_server/component_metadata_server_impl.h create mode 100644 src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h diff --git a/src/mavsdk/plugins/component_information_server/component_information_server.cpp b/src/mavsdk/plugins/component_information_server/component_information_server.cpp deleted file mode 100644 index 22eddb9e80..0000000000 --- a/src/mavsdk/plugins/component_information_server/component_information_server.cpp +++ /dev/null @@ -1,117 +0,0 @@ -// 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/component_information_server/component_information_server.proto) - -#include - -#include "component_information_server_impl.h" -#include "plugins/component_information_server/component_information_server.h" - -namespace mavsdk { - -using FloatParam = ComponentInformationServer::FloatParam; -using FloatParamUpdate = ComponentInformationServer::FloatParamUpdate; - -ComponentInformationServer::ComponentInformationServer( - std::shared_ptr server_component) : - ServerPluginBase(), - _impl{std::make_unique(server_component)} -{} - -ComponentInformationServer::~ComponentInformationServer() {} - -ComponentInformationServer::Result -ComponentInformationServer::provide_float_param(FloatParam param) const -{ - return _impl->provide_float_param(param); -} - -ComponentInformationServer::FloatParamHandle -ComponentInformationServer::subscribe_float_param(const FloatParamCallback& callback) -{ - return _impl->subscribe_float_param(callback); -} - -void ComponentInformationServer::unsubscribe_float_param(FloatParamHandle handle) -{ - _impl->unsubscribe_float_param(handle); -} - -bool operator==( - const ComponentInformationServer::FloatParam& lhs, - const ComponentInformationServer::FloatParam& rhs) -{ - return (rhs.name == lhs.name) && (rhs.short_description == lhs.short_description) && - (rhs.long_description == lhs.long_description) && (rhs.unit == lhs.unit) && - (rhs.decimal_places == lhs.decimal_places) && - ((std::isnan(rhs.start_value) && std::isnan(lhs.start_value)) || - rhs.start_value == lhs.start_value) && - ((std::isnan(rhs.default_value) && std::isnan(lhs.default_value)) || - rhs.default_value == lhs.default_value) && - ((std::isnan(rhs.min_value) && std::isnan(lhs.min_value)) || - rhs.min_value == lhs.min_value) && - ((std::isnan(rhs.max_value) && std::isnan(lhs.max_value)) || - rhs.max_value == lhs.max_value); -} - -std::ostream& -operator<<(std::ostream& str, ComponentInformationServer::FloatParam const& float_param) -{ - str << std::setprecision(15); - str << "float_param:" << '\n' << "{\n"; - str << " name: " << float_param.name << '\n'; - str << " short_description: " << float_param.short_description << '\n'; - str << " long_description: " << float_param.long_description << '\n'; - str << " unit: " << float_param.unit << '\n'; - str << " decimal_places: " << float_param.decimal_places << '\n'; - str << " start_value: " << float_param.start_value << '\n'; - str << " default_value: " << float_param.default_value << '\n'; - str << " min_value: " << float_param.min_value << '\n'; - str << " max_value: " << float_param.max_value << '\n'; - str << '}'; - return str; -} - -bool operator==( - const ComponentInformationServer::FloatParamUpdate& lhs, - const ComponentInformationServer::FloatParamUpdate& rhs) -{ - return (rhs.name == lhs.name) && - ((std::isnan(rhs.value) && std::isnan(lhs.value)) || rhs.value == lhs.value); -} - -std::ostream& operator<<( - std::ostream& str, ComponentInformationServer::FloatParamUpdate const& float_param_update) -{ - str << std::setprecision(15); - str << "float_param_update:" << '\n' << "{\n"; - str << " name: " << float_param_update.name << '\n'; - str << " value: " << float_param_update.value << '\n'; - str << '}'; - return str; -} - -std::ostream& operator<<(std::ostream& str, ComponentInformationServer::Result const& result) -{ - switch (result) { - case ComponentInformationServer::Result::Unknown: - return str << "Unknown"; - case ComponentInformationServer::Result::Success: - return str << "Success"; - case ComponentInformationServer::Result::DuplicateParam: - return str << "Duplicate Param"; - case ComponentInformationServer::Result::InvalidParamStartValue: - return str << "Invalid Param Start Value"; - case ComponentInformationServer::Result::InvalidParamDefaultValue: - return str << "Invalid Param Default Value"; - case ComponentInformationServer::Result::InvalidParamName: - return str << "Invalid Param Name"; - case ComponentInformationServer::Result::NoSystem: - return str << "No System"; - default: - return str << "Unknown"; - } -} - -} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/component_information_server/component_information_server_impl.cpp b/src/mavsdk/plugins/component_information_server/component_information_server_impl.cpp deleted file mode 100644 index 822b8c2bff..0000000000 --- a/src/mavsdk/plugins/component_information_server/component_information_server_impl.cpp +++ /dev/null @@ -1,189 +0,0 @@ -#include "component_information_server_impl.h" -#include "mavlink_address.h" -#include "mavlink_request_message_handler.h" -#include "callback_list.tpp" - -#include -#include -#include - -namespace mavsdk { - -template class CallbackList; - -ComponentInformationServerImpl::ComponentInformationServerImpl( - std::shared_ptr server_component) : - ServerPluginImplBase(server_component) -{ - // FIXME: allow other component IDs - _server_component_impl->register_plugin(this); -} - -ComponentInformationServerImpl::~ComponentInformationServerImpl() -{ - _server_component_impl->register_plugin(this); -} - -void ComponentInformationServerImpl::init() -{ - _server_component_impl->mavlink_request_message_handler().register_handler( - MAVLINK_MSG_ID_COMPONENT_INFORMATION, - [this](uint8_t, uint8_t, MavlinkRequestMessageHandler::Params) { - return process_component_information_requested(); - }, - this); -} - -void ComponentInformationServerImpl::deinit() -{ - _server_component_impl->mavlink_request_message_handler().unregister_all_handlers(this); -} - -ComponentInformationServer::Result -ComponentInformationServerImpl::provide_float_param(ComponentInformationServer::FloatParam param) -{ - std::lock_guard lock(_mutex); - - if (std::find_if( - _float_params.begin(), - _float_params.end(), - [&](ComponentInformationServer::FloatParam& existing_param) { - return existing_param.name == param.name; - }) != std::end(_float_params)) { - return ComponentInformationServer::Result::DuplicateParam; - } - - if (param.start_value > param.max_value || param.start_value < param.min_value) { - return ComponentInformationServer::Result::InvalidParamStartValue; - } - - if (param.default_value > param.max_value || param.default_value < param.min_value) { - return ComponentInformationServer::Result::InvalidParamDefaultValue; - } - - if (param.name.size() > 16) { - return ComponentInformationServer::Result::InvalidParamName; - } - - _float_params.push_back(param); - - update_json_files_with_lock(); - - _server_component_impl->mavlink_parameter_server().provide_server_param_float( - param.name, param.start_value); - _server_component_impl->mavlink_parameter_server().subscribe_param_float_changed( - param.name, - [this, name = param.name](float new_value) { param_update(name, new_value); }, - this); - - return ComponentInformationServer::Result::Success; -} - -ComponentInformationServer::FloatParamHandle ComponentInformationServerImpl::subscribe_float_param( - const ComponentInformationServer::FloatParamCallback& callback) -{ - std::lock_guard lock(_mutex); - return _float_param_update_callbacks.subscribe(callback); -} - -void ComponentInformationServerImpl::unsubscribe_float_param( - ComponentInformationServer::FloatParamHandle handle) -{ - std::lock_guard lock(_mutex); - _float_param_update_callbacks.unsubscribe(handle); -} - -void ComponentInformationServerImpl::param_update(const std::string& name, float new_value) -{ - std::lock_guard lock(_mutex); - ComponentInformationServer::FloatParamUpdate param_update{name, new_value}; - _float_param_update_callbacks.queue(param_update, [this](const auto& func) { - _server_component_impl->call_user_callback(func); - }); -} - -std::optional ComponentInformationServerImpl::process_component_information_requested() -{ - const char general_metadata_uri[100] = "mftp://general.json"; - const char peripherals_metadata_uri[100] = ""; - _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { - mavlink_message_t message; - mavlink_msg_component_information_pack_chan( - mavlink_address.system_id, - mavlink_address.component_id, - channel, - &message, - _server_component_impl->get_time().elapsed_ms(), - 0, - general_metadata_uri, - 0, - peripherals_metadata_uri); - return message; - }); - - // FIXME: REMOVE again - update_json_files_with_lock(); - - return MAV_RESULT_ACCEPTED; -} - -void ComponentInformationServerImpl::update_json_files_with_lock() -{ - auto parameter_file = generate_parameter_file(); - auto meta_file = generate_meta_file(); - - // std::cout << "parameter: " << parameter_file << '\n'; - // std::cout << "meta: " << meta_file << '\n'; - - // FIXME: needs refactoring - //_server_component_impl->mavlink_ftp().write_tmp_file("general.json", - // meta_file); - //_server_component_impl->mavlink_ftp().write_tmp_file("parameter.json", - // parameter_file); -} - -std::string ComponentInformationServerImpl::generate_parameter_file() -{ - Json::Value root; - root["version"] = 1; - Json::Value parameters = Json::arrayValue; - for (const auto& param : _float_params) { - Json::Value parameter; - parameter["name"] = param.name; - parameter["type"] = "Float"; - parameter["shortDesc"] = param.short_description; - parameter["longDesc"] = param.long_description; - parameter["units"] = param.unit; - parameter["decimalPlaces"] = param.decimal_places; - parameter["min"] = static_cast(param.min_value); - parameter["max"] = static_cast(param.max_value); - parameter["default"] = static_cast(param.default_value); - parameters.append(parameter); - } - root["parameters"] = parameters; - - return root.toStyledString(); -} - -std::string ComponentInformationServerImpl::generate_meta_file() -{ - Json::Value root; - root["version"] = 1; - root["vendorName"] = "Vendor"; - root["modelName"] = "Model"; - root["firmwareVersion"] = "1.0.0.0"; - root["hardwareVersion"] = "1.0.0.0"; - Json::Value metadata_types = Json::arrayValue; - Json::Value metadata_type; - metadata_type["type"] = Json::Int{COMP_METADATA_TYPE_PARAMETER}; - metadata_type["uri"] = "mftp://parameter.json"; - metadata_type["fileCrc"] = 0; // TODO - metadata_type["uriFallback"] = ""; // TODO - metadata_type["fileCrcFallback"] = 0; - metadata_types.append(metadata_type); - root["metadataTypes"] = metadata_types; - - return root.toStyledString(); -} - -} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_information_server/component_information_server_impl.h b/src/mavsdk/plugins/component_information_server/component_information_server_impl.h deleted file mode 100644 index 8a245ca197..0000000000 --- a/src/mavsdk/plugins/component_information_server/component_information_server_impl.h +++ /dev/null @@ -1,41 +0,0 @@ -#pragma once - -#include "plugins/component_information_server/component_information_server.h" -#include "server_plugin_impl_base.h" -#include "callback_list.h" - -namespace mavsdk { - -class ComponentInformationServerImpl : public ServerPluginImplBase { -public: - explicit ComponentInformationServerImpl(std::shared_ptr server_component); - ~ComponentInformationServerImpl() override; - - void init() override; - void deinit() override; - - ComponentInformationServer::Result set_our_ip(const std::string& ip); - - ComponentInformationServer::Result - provide_float_param(ComponentInformationServer::FloatParam param); - - ComponentInformationServer::FloatParamHandle - subscribe_float_param(const ComponentInformationServer::FloatParamCallback& callback); - void unsubscribe_float_param(ComponentInformationServer::FloatParamHandle handle); - -private: - void update_json_files_with_lock(); - void param_update(const std::string& name, float new_value); - - std::string generate_parameter_file(); - std::string generate_meta_file(); - - std::optional process_component_information_requested(); - - std::mutex _mutex{}; - std::vector _float_params{}; - std::string _our_ip{}; - CallbackList _float_param_update_callbacks{}; -}; - -} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_information_server/include/plugins/component_information_server/component_information_server.h b/src/mavsdk/plugins/component_information_server/include/plugins/component_information_server/component_information_server.h deleted file mode 100644 index 28744b80c6..0000000000 --- a/src/mavsdk/plugins/component_information_server/include/plugins/component_information_server/component_information_server.h +++ /dev/null @@ -1,177 +0,0 @@ -// 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/component_information_server/component_information_server.proto) - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "server_plugin_base.h" - -#include "handle.h" - -namespace mavsdk { - -class ServerComponent; -class ComponentInformationServerImpl; - -/** - * @brief Provide component information such as parameters. - */ -class ComponentInformationServer : public ServerPluginBase { -public: - /** - * @brief Constructor. Creates the plugin for a ServerComponent instance. - * - * The plugin is typically created as shown below: - * - * ```cpp - * auto component_information_server = ComponentInformationServer(server_component); - * ``` - * - * @param server_component The ServerComponent instance associated with this server plugin. - */ - explicit ComponentInformationServer(std::shared_ptr server_component); - - /** - * @brief Destructor (internal use only). - */ - ~ComponentInformationServer() override; - - /** - * @brief Meta information for parameter of type float. - */ - struct FloatParam { - std::string name{}; /**< @brief Name (max 16 chars) */ - std::string short_description{}; /**< @brief Short description */ - std::string long_description{}; /**< @brief Long description */ - std::string unit{}; /**< @brief Unit */ - int32_t decimal_places{}; /**< @brief Decimal places for user to show */ - float start_value{}; /**< @brief Current/starting value */ - float default_value{}; /**< @brief Default value */ - float min_value{}; /**< @brief Minimum value */ - float max_value{}; /**< @brief Maximum value */ - }; - - /** - * @brief Equal operator to compare two `ComponentInformationServer::FloatParam` objects. - * - * @return `true` if items are equal. - */ - friend bool operator==( - const ComponentInformationServer::FloatParam& lhs, - const ComponentInformationServer::FloatParam& rhs); - - /** - * @brief Stream operator to print information about a `ComponentInformationServer::FloatParam`. - * - * @return A reference to the stream. - */ - friend std::ostream& - operator<<(std::ostream& str, ComponentInformationServer::FloatParam const& float_param); - - /** - * @brief A float param that has been updated. - */ - struct FloatParamUpdate { - std::string name{}; /**< @brief Name of param that changed */ - float value{}; /**< @brief New value of param */ - }; - - /** - * @brief Equal operator to compare two `ComponentInformationServer::FloatParamUpdate` objects. - * - * @return `true` if items are equal. - */ - friend bool operator==( - const ComponentInformationServer::FloatParamUpdate& lhs, - const ComponentInformationServer::FloatParamUpdate& rhs); - - /** - * @brief Stream operator to print information about a - * `ComponentInformationServer::FloatParamUpdate`. - * - * @return A reference to the stream. - */ - friend std::ostream& operator<<( - std::ostream& str, ComponentInformationServer::FloatParamUpdate const& float_param_update); - - /** - * @brief Possible results returned for param requests. - */ - enum class Result { - Unknown, /**< @brief Unknown result. */ - Success, /**< @brief Request succeeded. */ - DuplicateParam, /**< @brief Duplicate param. */ - InvalidParamStartValue, /**< @brief Invalid start param value. */ - InvalidParamDefaultValue, /**< @brief Invalid default param value. */ - InvalidParamName, /**< @brief Invalid param name. */ - NoSystem, /**< @brief No system is connected. */ - }; - - /** - * @brief Stream operator to print information about a `ComponentInformationServer::Result`. - * - * @return A reference to the stream. - */ - friend std::ostream& - operator<<(std::ostream& str, ComponentInformationServer::Result const& result); - - /** - * @brief Callback type for asynchronous ComponentInformationServer calls. - */ - using ResultCallback = std::function; - - /** - * @brief Provide a param of type float. - * - * This function is blocking. - * - * @return Result of request. - */ - Result provide_float_param(FloatParam param) const; - - /** - * @brief Callback type for subscribe_float_param. - */ - using FloatParamCallback = std::function; - - /** - * @brief Handle type for subscribe_float_param. - */ - using FloatParamHandle = Handle; - - /** - * @brief Subscribe to float param updates. - */ - FloatParamHandle subscribe_float_param(const FloatParamCallback& callback); - - /** - * @brief Unsubscribe from subscribe_float_param - */ - void unsubscribe_float_param(FloatParamHandle handle); - - /** - * @brief Copy constructor. - */ - ComponentInformationServer(const ComponentInformationServer& other); - - /** - * @brief Equality operator (object is not copyable). - */ - const ComponentInformationServer& operator=(const ComponentInformationServer&) = 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/plugins/component_information_server/CMakeLists.txt b/src/mavsdk/plugins/component_metadata_server/CMakeLists.txt similarity index 64% rename from src/mavsdk/plugins/component_information_server/CMakeLists.txt rename to src/mavsdk/plugins/component_metadata_server/CMakeLists.txt index dd59e6951c..5bdc9397a6 100644 --- a/src/mavsdk/plugins/component_information_server/CMakeLists.txt +++ b/src/mavsdk/plugins/component_metadata_server/CMakeLists.txt @@ -1,7 +1,7 @@ target_sources(mavsdk PRIVATE - component_information_server.cpp - component_information_server_impl.cpp + component_metadata_server.cpp + component_metadata_server_impl.cpp ) target_include_directories(mavsdk PUBLIC @@ -10,6 +10,6 @@ target_include_directories(mavsdk PUBLIC ) install(FILES - include/plugins/component_information_server/component_information_server.h + include/plugins/component_metadata_server/component_metadata_server.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/mavsdk/plugins/component_information_server ) diff --git a/src/mavsdk/plugins/component_metadata_server/component_metadata_server.cpp b/src/mavsdk/plugins/component_metadata_server/component_metadata_server.cpp new file mode 100644 index 0000000000..803bf3ff17 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata_server/component_metadata_server.cpp @@ -0,0 +1,23 @@ +// 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/component_metadata_server/component_metadata_server.proto) + +#include "component_metadata_server_impl.h" +#include "plugins/component_metadata_server/component_metadata_server.h" + +namespace mavsdk { + +ComponentMetadataServer::ComponentMetadataServer( + std::shared_ptr server_component) : + ServerPluginBase(), + _impl{std::make_unique(server_component)} +{} + +ComponentMetadataServer::~ComponentMetadataServer() {} +void ComponentMetadataServer::set_metadata(const std::vector& metadata) +{ + _impl->set_metadata(metadata); +} + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/component_metadata_server/component_metadata_server_impl.cpp b/src/mavsdk/plugins/component_metadata_server/component_metadata_server_impl.cpp new file mode 100644 index 0000000000..1d67f6f682 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata_server/component_metadata_server_impl.cpp @@ -0,0 +1,174 @@ +#include "component_metadata_server_impl.h" +#include "mavlink_address.h" +#include "mavlink_request_message_handler.h" +#include "callback_list.tpp" +#include "fs_utils.h" +#include "crc32.h" + +#include +#include + +namespace mavsdk { + +ComponentMetadataServerImpl::ComponentMetadataServerImpl( + std::shared_ptr server_component) : + ServerPluginImplBase(server_component) +{ + 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; + } + } + + _server_component_impl->register_plugin(this); +} + +ComponentMetadataServerImpl::~ComponentMetadataServerImpl() +{ + _server_component_impl->unregister_plugin(this); + if (_metadata_set) { + std::filesystem::remove_all(_tmp_path); + } +} + +void ComponentMetadataServerImpl::init() +{ + _server_component_impl->mavlink_request_message_handler().register_handler( + MAVLINK_MSG_ID_COMPONENT_METADATA, + [this]( + uint8_t source_sys_id, uint8_t source_comp_id, MavlinkRequestMessageHandler::Params) { + return process_component_metadata_requested(); + }, + this); +} + +void ComponentMetadataServerImpl::deinit() +{ + _server_component_impl->mavlink_request_message_handler().unregister_all_handlers(this); +} + +std::optional ComponentMetadataServerImpl::process_component_metadata_requested() +{ + if (_verbose_debugging) { + LogDebug() << "MAVLINK_MSG_ID_COMPONENT_METADATA request received"; + } + + const std::lock_guard lg{_mutex}; + + if (!_metadata_set) { + return MAV_RESULT_TEMPORARILY_REJECTED; + } + + char general_metadata_uri[MAVLINK_MSG_COMPONENT_METADATA_FIELD_URI_LEN]; + snprintf( + general_metadata_uri, sizeof(general_metadata_uri), "mftp://%s", kComponentGeneralFilename); + _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message; + mavlink_msg_component_metadata_pack_chan( + mavlink_address.system_id, + mavlink_address.component_id, + channel, + &message, + _server_component_impl->get_time().elapsed_ms(), + _comp_info_general_crc, + general_metadata_uri); + return message; + }); + + return MAV_RESULT_ACCEPTED; +} +void ComponentMetadataServerImpl::set_metadata( + const std::vector& metadata) +{ + const std::lock_guard lg{_mutex}; + if (_metadata_set) { + LogErr() << "metadata already set"; + return; + } + + // Create tmp directory as ftp root directory + const auto tmp_option = create_tmp_directory("mavsdk-component-metadata-server"); + if (!tmp_option) { + LogErr() << "Failed to create tmp directory"; + return; + } + _tmp_path = *tmp_option; + + if (_verbose_debugging) { + LogDebug() << "Storing metadata under " << _tmp_path; + } + + // Write files + for (const auto& single_metadata : metadata) { + Crc32 crc{}; + crc.add( + reinterpret_cast(single_metadata.json_metadata.data()), + single_metadata.json_metadata.length()); + + _metadata.emplace_back(single_metadata.type, crc.get()); + const std::filesystem::path path = _tmp_path / _metadata.back().filename; + std::ofstream file(path, std::fstream::trunc | std::fstream::binary | std::fstream::out); + if (!file) { + LogErr() << "Failed to open " << path; + continue; + } + file.write(single_metadata.json_metadata.data(), single_metadata.json_metadata.length()); + } + + if (!generate_component_metadata_general_file()) { + return; + } + + _metadata_set = true; + _server_component_impl->mavlink_ftp_server().set_root_directory(_tmp_path.string()); +} + +bool ComponentMetadataServerImpl::generate_component_metadata_general_file() +{ + Json::Value root; + root["version"] = 1; + Json::Value metadata_types = Json::arrayValue; + for (const auto& metadata : _metadata) { + Json::Value metadata_type; + metadata_type["type"] = Json::Int{metadata.type}; + metadata_type["uri"] = "mftp://" + metadata.filename; + metadata_type["fileCrc"] = Json::UInt{metadata.crc}; + metadata_types.append(metadata_type); + } + root["metadataTypes"] = metadata_types; + + const std::filesystem::path path = _tmp_path / kComponentGeneralFilename; + std::ofstream file(path, std::fstream::trunc | std::fstream::binary | std::fstream::out); + if (!file) { + LogErr() << "Failed to open " << path; + return false; + } + const std::string json_data = root.toStyledString(); + Crc32 crc{}; + crc.add(reinterpret_cast(json_data.data()), json_data.length()); + _comp_info_general_crc = crc.get(); + file.write(json_data.data(), json_data.length()); + return true; +} + +ComponentMetadataServerImpl::Metadata::Metadata( + ComponentMetadataServer::MetadataType metadata_type, uint32_t crc_data) : + crc(crc_data) +{ + switch (metadata_type) { + case ComponentMetadataServer::MetadataType::Parameter: + type = COMP_METADATA_TYPE_PARAMETER; + filename = "parameters.json"; + break; + case ComponentMetadataServer::MetadataType::Events: + type = COMP_METADATA_TYPE_EVENTS; + filename = "events.json"; + break; + case ComponentMetadataServer::MetadataType::Actuators: + type = COMP_METADATA_TYPE_ACTUATORS; + filename = "actuators.json"; + break; + } +} +} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_metadata_server/component_metadata_server_impl.h b/src/mavsdk/plugins/component_metadata_server/component_metadata_server_impl.h new file mode 100644 index 0000000000..5b2bc994d4 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata_server/component_metadata_server_impl.h @@ -0,0 +1,44 @@ +#pragma once + +#include "plugins/component_metadata_server/component_metadata_server.h" +#include "server_plugin_impl_base.h" +#include "callback_list.h" +#include + +namespace mavsdk { + +class ComponentMetadataServerImpl : public ServerPluginImplBase { +public: + explicit ComponentMetadataServerImpl(std::shared_ptr server_component); + ~ComponentMetadataServerImpl() override; + + void init() override; + void deinit() override; + + void set_metadata(const std::vector& metadata); + +private: + struct Metadata { + explicit Metadata(ComponentMetadataServer::MetadataType metadata_type, uint32_t crc_data); + + COMP_METADATA_TYPE type; + std::string filename; + uint32_t crc; + }; + + bool generate_component_metadata_general_file(); + std::optional process_component_metadata_requested(); + + static constexpr const char* kComponentGeneralFilename = "comp_general.json"; + + std::mutex _mutex{}; ///< protect concurrent access to any of the class members + + std::vector _metadata; + bool _metadata_set{false}; + std::filesystem::path _tmp_path; ///< ftp root dir + + uint32_t _comp_info_general_crc{}; + bool _verbose_debugging{false}; +}; + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h b/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h new file mode 100644 index 0000000000..36ed76c8c0 --- /dev/null +++ b/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h @@ -0,0 +1,77 @@ +// 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/component_metadata_server/component_metadata_server.proto) + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "server_plugin_base.h" + +#include "handle.h" + +namespace mavsdk { + +class ServerComponent; +class ComponentMetadataServerImpl; + +/** + * @brief Provide component metadata such as parameters. + */ +class ComponentMetadataServer : public ServerPluginBase { +public: + /** + * @brief Constructor. Creates the plugin for a ServerComponent instance. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto component_metadata_server = ComponentMetadataServer(server_component); + * ``` + * + * @param server_component The ServerComponent instance associated with this server plugin. + */ + explicit ComponentMetadataServer(std::shared_ptr server_component); + + /** + * @brief Destructor (internal use only). + */ + ~ComponentMetadataServer() override; + + enum class MetadataType { + Parameter, + Events, + Actuators, + }; + + struct Metadata { + MetadataType type; + std::string json_data; + }; + + void set_metadata(const std::vector& metadata); + + /** + * @brief Copy constructor. + */ + ComponentMetadataServer(const ComponentMetadataServer& other); + + /** + * @brief Equality operator (object is not copyable). + */ + const ComponentMetadataServer& operator=(const ComponentMetadataServer&) = delete; + +private: + /** @private Underlying implementation, set at instantiation */ + std::unique_ptr _impl; +}; + +} // namespace mavsdk \ No newline at end of file diff --git a/src/plugins.txt b/src/plugins.txt index 3eed57c61f..5b058230f7 100644 --- a/src/plugins.txt +++ b/src/plugins.txt @@ -5,7 +5,7 @@ calibration camera camera_server component_metadata -component_information_server +component_metadata_server failure follow_me ftp From 1b0673453f5ccc23eb030beab469c03f51f30479 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 4 Apr 2024 20:01:47 +0200 Subject: [PATCH 09/15] system_tests: add test for component_metadata --- src/system_tests/CMakeLists.txt | 2 +- src/system_tests/component_information.cpp | 68 ------ src/system_tests/component_metadata.cpp | 230 +++++++++++++++++++++ 3 files changed, 231 insertions(+), 69 deletions(-) delete mode 100644 src/system_tests/component_information.cpp create mode 100644 src/system_tests/component_metadata.cpp diff --git a/src/system_tests/CMakeLists.txt b/src/system_tests/CMakeLists.txt index 068087c940..83c72ade44 100644 --- a/src/system_tests/CMakeLists.txt +++ b/src/system_tests/CMakeLists.txt @@ -1,6 +1,6 @@ add_executable(system_tests_runner camera_take_photo.cpp - component_information.cpp + component_metadata.cpp action_arm_disarm.cpp param_set_and_get.cpp param_get_all.cpp diff --git a/src/system_tests/component_information.cpp b/src/system_tests/component_information.cpp deleted file mode 100644 index 2a6b143cb9..0000000000 --- a/src/system_tests/component_information.cpp +++ /dev/null @@ -1,68 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include "mavsdk.h" -#include "log.h" -#include "plugins/component_information/component_information.h" -#include "plugins/component_information_server/component_information_server.h" -#include "plugins/param/param.h" -#include - -using namespace mavsdk; - -// Disabled for now because the mavlink ftp plugin is not available properly on -// the server side right now. It needs to be split into client and server and -// split across system_impl, and server_component_impl. -TEST(SystemTest, DISABLED_ComponentInformationConnect) -{ - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; - ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); - - Mavsdk mavsdk_companion{Mavsdk::Configuration{Mavsdk::ComponentType::CompanionComputer}}; - ASSERT_EQ( - mavsdk_companion.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - - auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); - ASSERT_TRUE(maybe_system); - auto system = maybe_system.value(); - - auto server = ComponentInformationServer{mavsdk_companion.server_component()}; - - auto param = ComponentInformationServer::FloatParam{}; - param.name = "ANG_RATE_ACC_MAX"; - param.short_description = "Angular rate acceleration maximum."; - param.long_description = "The lower the maximum angular rate acceleration, " - "the smoother the gimbal will react to user input."; - param.unit = "rad/s^2"; - param.min_value = 1.0f; - param.max_value = 10.0f; - param.default_value = 3.0f; - param.start_value = 4.0f; - param.decimal_places = 1; - - server.provide_float_param(param); - - server.subscribe_float_param([](ComponentInformationServer::FloatParamUpdate param_update) { - LogInfo() << "Param " << param_update.name << " changed to " << param_update.value - << " on server side"; - }); - - auto param_client = Param{system}; - - param_client.set_param_float("ANG_RATE_ACC_MAX", 5.0f); - - auto client = ComponentInformation{system}; - client.subscribe_float_param([](ComponentInformation::FloatParamUpdate param_update) { - LogInfo() << "Param " << param_update.name << " changed to " << param_update.value - << " on client side"; - }); - - // Use another parameter to trigger the second callback. - param_client.set_param_float("ANG_RATE_ACC_MAX", 6.0f); - - std::this_thread::sleep_for(std::chrono::milliseconds(100)); -} diff --git a/src/system_tests/component_metadata.cpp b/src/system_tests/component_metadata.cpp new file mode 100644 index 0000000000..3503456f60 --- /dev/null +++ b/src/system_tests/component_metadata.cpp @@ -0,0 +1,230 @@ +#include +#include +#include +#include +#include +#include + +#include "mavsdk.h" +#include "log.h" +#include "plugins/component_metadata/component_metadata.h" +#include "plugins/component_metadata_server/component_metadata_server.h" +#include + +using namespace mavsdk; + +static constexpr const char* parameter_json_metadata = R"JSON({ + "parameters": [ + { + "category": "Standard", + "default": 1, + "group": "Autotune", + "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly.", + "name": "MC_AT_APPLY", + "shortDesc": "Controls when to apply the new gains", + "type": "Int32", + "values": [ + { + "description": "Do not apply the new gains (logging only)", + "value": 0 + }, + { + "description": "Apply the new gains after disarm", + "value": 1 + }, + { + "description": "WARNING Apply the new gains in air", + "value": 2 + } + ] + }, + { + "category": "Standard", + "default": 0, + "group": "Autotune", + "name": "MC_AT_EN", + "shortDesc": "Multicopter autotune module enable", + "type": "Int32", + "values": [ + { + "description": "Disabled", + "value": 0 + }, + { + "description": "Enabled", + "value": 1 + } + ] + }, + { + "category": "Standard", + "decimalPlaces": 2, + "default": 0.14, + "group": "Autotune", + "max": 0.5, + "min": 0.01, + "name": "MC_AT_RISE_TIME", + "shortDesc": "Desired angular rate closed-loop rise time", + "type": "Float", + "units": "s" + }, + { + "category": "Standard", + "default": 0, + "group": "Autotune", + "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio", + "name": "MC_AT_START", + "shortDesc": "Start the autotuning sequence", + "type": "Int32", + "values": [ + { + "description": "Disabled", + "value": 0 + }, + { + "description": "Enabled", + "value": 1 + } + ] + }, + { + "category": "Standard", + "decimalPlaces": 1, + "default": 0.7, + "group": "Autotune", + "max": 6.0, + "min": 0.1, + "name": "MC_AT_SYSID_AMP", + "shortDesc": "Amplitude of the injected signal", + "type": "Float" + }, + { + "category": "Standard", + "decimalPlaces": 0, + "default": -1.0, + "group": "Battery Calibration", + "increment": 50.0, + "longDesc": "Defines the capacity of battery 1 in mAh.", + "max": 100000.0, + "min": -1.0, + "name": "BAT1_CAPACITY", + "rebootRequired": true, + "shortDesc": "Battery 1 capacity", + "type": "Float", + "units": "mAh" + } + }, + "version": 1 +} +)JSON"; + +static constexpr const char* events_json_metadata = R"JSON({ + "components": { + "1": { + "event_groups": { + "default": { + "events": { + "10072599": { + "message": "Calibration: Disabling RC input", + "name": "commander_calib_rc_off" + }, + "10162376": { + "message": "Mission land item could not be read", + "name": "rtl_failed_to_read_land_item" + }, + "10229254": { + "arguments": [ + { + "name": "arg0", + "type": "int32_t" + } + ], + "message": "RTL Mission Land: climb to {1m_v}", + "name": "rtl_mission_land_climb" + }, + "10452355": { + "message": "Takeoff airspeed reached, climbout", + "name": "runway_takeoff_reached_airspeed" + }, + "10493596": { + "message": "Airspeed sensor failure detected. Return to launch (RTL) is advised", + "name": "airspeed_selector_sensor_failure" + } + } + } + } + }, + "version": 2 +} +)JSON"; + +TEST(SystemTest, ComponentInformationConnect) +{ + // Enable more debug output +#ifndef WINDOWS // setenv is not available on Windows + setenv("MAVSDK_COMPONENT_METADATA_DEBUGGING", "1", 1); +#endif + + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); + + Mavsdk mavsdk_companion{Mavsdk::Configuration{Mavsdk::ComponentType::CompanionComputer}}; + ASSERT_EQ( + mavsdk_companion.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); + + // Wait for companion system to connect + auto prom = std::promise>(); + std::once_flag flag; + mavsdk_groundstation.subscribe_on_new_system([&]() { + std::call_once(flag, [&prom, &mavsdk_groundstation]() { + prom.set_value(mavsdk_groundstation.systems().at(0)); + }); + }); + auto fut = prom.get_future(); + ASSERT_EQ(fut.wait_for(std::chrono::seconds(5)), std::future_status::ready); + auto system = fut.get(); + + auto server = ComponentMetadataServer{mavsdk_companion.server_component()}; + + // Register metadata + std::vector metadata; + metadata.push_back( + {ComponentMetadataServer::MetadataType::Parameter, std::string(parameter_json_metadata)}); + metadata.push_back( + {ComponentMetadataServer::MetadataType::Events, std::string(events_json_metadata)}); + server.set_metadata(metadata); + + // Ask for metadata + auto client = ComponentMetadata{system}; + client.request_component(MAV_COMP_ID_ONBOARD_COMPUTER); + std::atomic_bool received_parameters{false}; + std::atomic_bool received_events{false}; + std::atomic_bool all_completed{false}; + client.subscribe_metadata_available([&received_events, &received_parameters, &all_completed]( + ComponentMetadata::MetadataUpdate data) { + LogInfo() << "Got metadata, type: " << static_cast(data.type); + EXPECT_EQ(data.compid, MAV_COMP_ID_ONBOARD_COMPUTER); + switch (data.type) { + case ComponentMetadata::MetadataType::Parameter: + EXPECT_EQ(data.json_metadata, parameter_json_metadata); + received_parameters = true; + break; + case ComponentMetadata::MetadataType::Events: + EXPECT_EQ(data.json_metadata, events_json_metadata); + received_events = true; + break; + case ComponentMetadata::MetadataType::AllCompleted: + all_completed = true; + break; + default: + ASSERT_TRUE(false) << "Unexpected metadata type " << static_cast(data.type); + } + }); + + for (int i = 0; i < 100 && (!received_events || !received_parameters || !all_completed); ++i) { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + ASSERT_TRUE(received_events) << "timeout, metadata not received"; + ASSERT_TRUE(received_parameters) << "timeout, metadata not received"; + ASSERT_TRUE(all_completed) << "timeout, metadata not received"; +} \ No newline at end of file From 3abc88fbeda25e563906163a3b6fefa9b0e9947b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 5 Apr 2024 10:21:59 +0200 Subject: [PATCH 10/15] mavlink_ftp_client: retry download if the other component already has an ongoing transfer --- src/mavsdk/core/mavlink_ftp_client.cpp | 21 +++++++++++++++------ src/mavsdk/core/mavlink_ftp_client.h | 2 +- 2 files changed, 16 insertions(+), 7 deletions(-) diff --git a/src/mavsdk/core/mavlink_ftp_client.cpp b/src/mavsdk/core/mavlink_ftp_client.cpp index 94e04c0643..3293fbc16e 100644 --- a/src/mavsdk/core/mavlink_ftp_client.cpp +++ b/src/mavsdk/core/mavlink_ftp_client.cpp @@ -204,10 +204,19 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } } else if (payload->opcode == RSP_NAK) { - LogWarn() << "FTP: NAK received"; - stop_timer(); - item.callback(result_from_nak(payload), {}); - work_queue_guard.pop_front(); + const ServerResult sr = static_cast(payload->data[0]); + // In case there's no session available, there's another transfer in progress + // for the given component. Back off and try again later. + if (sr == ERR_NO_SESSIONS_AVAILABLE) { + payload->seq_number = 0; // Ignore this response + start_timer(3.0); + LogDebug() << "No session available, retrying..."; + } else { + LogWarn() << "FTP: NAK received"; + stop_timer(); + item.callback(result_from_nak(payload), {}); + work_queue_guard.pop_front(); + } } }, [&](UploadItem& item) { @@ -1179,11 +1188,11 @@ void MavlinkFtpClient::send_mavlink_ftp_message(const PayloadHeader& payload, ui }); } -void MavlinkFtpClient::start_timer() +void MavlinkFtpClient::start_timer(std::optional duration_s) { _system_impl.unregister_timeout_handler(_timeout_cookie); _system_impl.register_timeout_handler( - [this]() { timeout(); }, _system_impl.timeout_s(), &_timeout_cookie); + [this]() { timeout(); }, duration_s.value_or(_system_impl.timeout_s()), &_timeout_cookie); } void MavlinkFtpClient::stop_timer() diff --git a/src/mavsdk/core/mavlink_ftp_client.h b/src/mavsdk/core/mavlink_ftp_client.h index 4c84f4b14e..20919c917b 100644 --- a/src/mavsdk/core/mavlink_ftp_client.h +++ b/src/mavsdk/core/mavlink_ftp_client.h @@ -299,7 +299,7 @@ class MavlinkFtpClient { static ClientResult result_from_nak(PayloadHeader* payload); void timeout(); - void start_timer(); + void start_timer(std::optional duration_s = {}); void stop_timer(); ClientResult calc_local_file_crc32(const std::string& path, uint32_t& csum); From 822b3f1da4e348f7922812a08cbf6630de6bf58e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 8 Apr 2024 14:48:02 +0200 Subject: [PATCH 11/15] mavlink_ftp_client: use _system_impl.call_user_callback instead of calling the callback directly. Otherwise if the callback tries to trigger a new request, it would block indefinitely when trying to add a work item to _work_queue, which is already locked by this: LockedQueue::Guard work_queue_guard(_work_queue); --- src/mavsdk/core/mavlink_ftp_client.cpp | 127 +++++++++++++++---------- src/mavsdk/core/mavlink_ftp_client.h | 7 ++ 2 files changed, 82 insertions(+), 52 deletions(-) diff --git a/src/mavsdk/core/mavlink_ftp_client.cpp b/src/mavsdk/core/mavlink_ftp_client.cpp index 3293fbc16e..49673f77a0 100644 --- a/src/mavsdk/core/mavlink_ftp_client.cpp +++ b/src/mavsdk/core/mavlink_ftp_client.cpp @@ -167,7 +167,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->req_opcode == CMD_TERMINATE_SESSION) { stop_timer(); item.ofstream.close(); - item.callback(ClientResult::Success, {}); + call_callback(item.callback, ClientResult::Success, {}); work_queue_guard.pop_front(); } else { @@ -176,7 +176,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->opcode == RSP_NAK) { stop_timer(); - item.callback(result_from_nak(payload), {}); + call_callback(item.callback, result_from_nak(payload), {}); work_queue_guard.pop_front(); } }, @@ -196,7 +196,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->req_opcode == CMD_TERMINATE_SESSION) { stop_timer(); item.ofstream.close(); - item.callback(ClientResult::Success, {}); + call_callback(item.callback, ClientResult::Success, {}); work_queue_guard.pop_front(); } else { @@ -214,7 +214,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else { LogWarn() << "FTP: NAK received"; stop_timer(); - item.callback(result_from_nak(payload), {}); + call_callback(item.callback, result_from_nak(payload), {}); work_queue_guard.pop_front(); } } @@ -235,7 +235,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->req_opcode == CMD_TERMINATE_SESSION) { stop_timer(); item.ifstream.close(); - item.callback(ClientResult::Success, {}); + call_callback(item.callback, ClientResult::Success, {}); work_queue_guard.pop_front(); } else { @@ -244,7 +244,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->opcode == RSP_NAK) { stop_timer(); - item.callback(result_from_nak(payload), {}); + call_callback(item.callback, result_from_nak(payload), {}); work_queue_guard.pop_front(); } }, @@ -252,7 +252,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) if (payload->opcode == RSP_ACK) { if (payload->req_opcode == CMD_REMOVE_FILE) { stop_timer(); - item.callback(ClientResult::Success); + call_callback(item.callback, ClientResult::Success); work_queue_guard.pop_front(); } else { @@ -261,7 +261,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->opcode == RSP_NAK) { stop_timer(); - item.callback(result_from_nak(payload)); + call_callback(item.callback, result_from_nak(payload)); work_queue_guard.pop_front(); } }, @@ -269,7 +269,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) if (payload->opcode == RSP_ACK) { if (payload->req_opcode == CMD_RENAME) { stop_timer(); - item.callback(ClientResult::Success); + call_callback(item.callback, ClientResult::Success); work_queue_guard.pop_front(); } else { @@ -278,7 +278,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->opcode == RSP_NAK) { stop_timer(); - item.callback(result_from_nak(payload)); + call_callback(item.callback, result_from_nak(payload)); work_queue_guard.pop_front(); } }, @@ -286,7 +286,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) if (payload->opcode == RSP_ACK) { if (payload->req_opcode == CMD_CREATE_DIRECTORY) { stop_timer(); - item.callback(ClientResult::Success); + call_callback(item.callback, ClientResult::Success); work_queue_guard.pop_front(); } else { @@ -295,7 +295,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->opcode == RSP_NAK) { stop_timer(); - item.callback(result_from_nak(payload)); + call_callback(item.callback, result_from_nak(payload)); work_queue_guard.pop_front(); } }, @@ -303,7 +303,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) if (payload->opcode == RSP_ACK) { if (payload->req_opcode == CMD_REMOVE_DIRECTORY) { stop_timer(); - item.callback(ClientResult::Success); + call_callback(item.callback, ClientResult::Success); work_queue_guard.pop_front(); } else { @@ -312,7 +312,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->opcode == RSP_NAK) { stop_timer(); - item.callback(result_from_nak(payload)); + call_callback(item.callback, result_from_nak(payload)); work_queue_guard.pop_front(); } }, @@ -321,7 +321,8 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) if (payload->req_opcode == CMD_CALC_FILE_CRC32) { stop_timer(); uint32_t remote_crc = *reinterpret_cast(payload->data); - item.callback(ClientResult::Success, remote_crc == item.local_crc); + call_callback( + item.callback, ClientResult::Success, remote_crc == item.local_crc); work_queue_guard.pop_front(); } else { @@ -330,7 +331,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) } else if (payload->opcode == RSP_NAK) { stop_timer(); - item.callback(result_from_nak(payload), false); + call_callback(item.callback, result_from_nak(payload), false); work_queue_guard.pop_front(); } }, @@ -352,9 +353,9 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg) stop_timer(); if (payload->data[0] == ERR_EOF) { std::sort(item.dirs.begin(), item.dirs.end()); - item.callback(ClientResult::Success, item.dirs); + call_callback(item.callback, ClientResult::Success, item.dirs); } else { - item.callback(result_from_nak(payload), {}); + call_callback(item.callback, result_from_nak(payload), {}); } work_queue_guard.pop_front(); } @@ -375,7 +376,7 @@ bool MavlinkFtpClient::download_start(Work& work, DownloadItem& item) item.ofstream.open(local_path, std::fstream::trunc | std::fstream::binary); if (!item.ofstream) { LogErr() << "Could not open it!"; - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); return false; } @@ -412,7 +413,7 @@ bool MavlinkFtpClient::download_continue(Work& work, DownloadItem& item, Payload if (item.bytes_transferred < item.file_size) { item.ofstream.write(reinterpret_cast(payload->data), payload->size); if (!item.ofstream) { - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); return false; } item.bytes_transferred += payload->size; @@ -422,7 +423,8 @@ bool MavlinkFtpClient::download_continue(Work& work, DownloadItem& item, Payload << " bytes"; } } - item.callback( + call_callback( + item.callback, ClientResult::Next, ProgressData{ static_cast(item.bytes_transferred), @@ -483,7 +485,7 @@ bool MavlinkFtpClient::download_burst_start(Work& work, DownloadBurstItem& item) item.ofstream.open(local_path, std::fstream::trunc | std::fstream::binary); if (!item.ofstream) { LogErr() << "Could not open it!"; - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); return false; } @@ -538,7 +540,7 @@ bool MavlinkFtpClient::download_burst_continue( item.ofstream.write(empty.data(), empty.size()); if (!item.ofstream) { LogWarn() << "Write failed"; - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); download_burst_end(work); return false; } @@ -548,7 +550,7 @@ bool MavlinkFtpClient::download_burst_continue( item.ofstream.write(reinterpret_cast(payload->data), payload->size); if (!item.ofstream) { LogWarn() << "Write failed"; - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); download_burst_end(work); return false; } @@ -577,7 +579,8 @@ bool MavlinkFtpClient::download_burst_continue( request_next_rest(work, item); } } else { - item.callback( + call_callback( + item.callback, ClientResult::Next, ProgressData{ static_cast(burst_bytes_transferred(item)), @@ -601,14 +604,14 @@ bool MavlinkFtpClient::download_burst_continue( item.ofstream.seekp(payload->offset); if (item.ofstream.fail()) { LogWarn() << "Seek failed"; - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); download_burst_end(work); return false; } item.ofstream.write(reinterpret_cast(payload->data), payload->size); if (!item.ofstream) { - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); download_burst_end(work); return false; } @@ -616,7 +619,7 @@ bool MavlinkFtpClient::download_burst_continue( auto& missing = item.missing_data.front(); if (missing.offset != payload->offset) { LogErr() << "Offset mismatch"; - item.callback(ClientResult::ProtocolError, {}); + call_callback(item.callback, ClientResult::ProtocolError, {}); download_burst_end(work); return false; } @@ -644,7 +647,8 @@ bool MavlinkFtpClient::download_burst_continue( // Final step download_burst_end(work); } else { - item.callback( + call_callback( + item.callback, ClientResult::Next, ProgressData{ static_cast(bytes_transferred), @@ -733,13 +737,13 @@ bool MavlinkFtpClient::upload_start(Work& work, UploadItem& item) { std::error_code ec; if (!fs::exists(item.local_file_path, ec)) { - item.callback(ClientResult::FileDoesNotExist, {}); + call_callback(item.callback, ClientResult::FileDoesNotExist, {}); return false; } item.ifstream.open(item.local_file_path, std::fstream::binary); if (!item.ifstream) { - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); return false; } @@ -754,7 +758,7 @@ bool MavlinkFtpClient::upload_start(Work& work, UploadItem& item) fs::path(item.remote_folder) / fs::path(item.local_file_path).filename(); if (remote_file_path.string().size() >= max_data_length) { - item.callback(ClientResult::InvalidParameter, {}); + call_callback(item.callback, ClientResult::InvalidParameter, {}); return false; } @@ -797,7 +801,7 @@ bool MavlinkFtpClient::upload_continue(Work& work, UploadItem& item) int bytes_read = item.ifstream.gcount(); if (!item.ifstream) { - item.callback(ClientResult::FileIoError, {}); + call_callback(item.callback, ClientResult::FileIoError, {}); return false; } @@ -823,7 +827,8 @@ bool MavlinkFtpClient::upload_continue(Work& work, UploadItem& item) send_mavlink_ftp_message(work.payload, work.target_compid); } - item.callback( + call_callback( + item.callback, ClientResult::Next, ProgressData{ static_cast(item.bytes_transferred), static_cast(item.file_size)}); @@ -834,7 +839,7 @@ bool MavlinkFtpClient::upload_continue(Work& work, UploadItem& item) bool MavlinkFtpClient::remove_start(Work& work, RemoveItem& item) { if (item.path.length() >= max_data_length) { - item.callback(ClientResult::InvalidParameter); + call_callback(item.callback, ClientResult::InvalidParameter); return false; } @@ -856,7 +861,7 @@ bool MavlinkFtpClient::remove_start(Work& work, RemoveItem& item) bool MavlinkFtpClient::rename_start(Work& work, RenameItem& item) { if (item.from_path.length() + item.to_path.length() + 1 >= max_data_length) { - item.callback(ClientResult::InvalidParameter); + call_callback(item.callback, ClientResult::InvalidParameter); return false; } @@ -884,7 +889,7 @@ bool MavlinkFtpClient::rename_start(Work& work, RenameItem& item) bool MavlinkFtpClient::create_dir_start(Work& work, CreateDirItem& item) { if (item.path.length() + 1 >= max_data_length) { - item.callback(ClientResult::InvalidParameter); + call_callback(item.callback, ClientResult::InvalidParameter); return false; } @@ -906,7 +911,7 @@ bool MavlinkFtpClient::create_dir_start(Work& work, CreateDirItem& item) bool MavlinkFtpClient::remove_dir_start(Work& work, RemoveDirItem& item) { if (item.path.length() + 1 >= max_data_length) { - item.callback(ClientResult::InvalidParameter); + call_callback(item.callback, ClientResult::InvalidParameter); return false; } @@ -928,13 +933,13 @@ bool MavlinkFtpClient::remove_dir_start(Work& work, RemoveDirItem& item) bool MavlinkFtpClient::compare_files_start(Work& work, CompareFilesItem& item) { if (item.remote_path.length() + 1 >= max_data_length) { - item.callback(ClientResult::InvalidParameter, false); + call_callback(item.callback, ClientResult::InvalidParameter, false); return false; } auto result_local = calc_local_file_crc32(item.local_path, item.local_crc); if (result_local != ClientResult::Success) { - item.callback(result_local, false); + call_callback(item.callback, result_local, false); return false; } @@ -957,7 +962,7 @@ bool MavlinkFtpClient::compare_files_start(Work& work, CompareFilesItem& item) bool MavlinkFtpClient::list_dir_start(Work& work, ListDirItem& item) { if (item.path.length() + 1 >= max_data_length) { - item.callback(ClientResult::InvalidParameter, {}); + call_callback(item.callback, ClientResult::InvalidParameter, {}); return false; } @@ -989,7 +994,7 @@ bool MavlinkFtpClient::list_dir_continue(Work& work, ListDirItem& item, PayloadH if (payload->size == 0) { std::sort(item.dirs.begin(), item.dirs.end()); - item.callback(ClientResult::Success, item.dirs); + call_callback(item.callback, ClientResult::Success, item.dirs); return false; } @@ -1216,7 +1221,7 @@ void MavlinkFtpClient::timeout() overloaded{ [&](DownloadItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout, {}); + call_callback(item.callback, ClientResult::Timeout, {}); work_queue_guard.pop_front(); return; } @@ -1229,7 +1234,7 @@ void MavlinkFtpClient::timeout() }, [&](DownloadBurstItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout, {}); + call_callback(item.callback, ClientResult::Timeout, {}); work_queue_guard.pop_front(); return; } @@ -1246,7 +1251,7 @@ void MavlinkFtpClient::timeout() if (item.current_offset == item.file_size && item.missing_data.empty()) { // We are done anyway. item.ofstream.close(); - item.callback(ClientResult::Success, {}); + call_callback(item.callback, ClientResult::Success, {}); download_burst_end(*work); work_queue_guard.pop_front(); } else { @@ -1273,7 +1278,7 @@ void MavlinkFtpClient::timeout() }, [&](UploadItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout, {}); + call_callback(item.callback, ClientResult::Timeout, {}); work_queue_guard.pop_front(); return; } @@ -1286,7 +1291,7 @@ void MavlinkFtpClient::timeout() }, [&](RemoveItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout); + call_callback(item.callback, ClientResult::Timeout); work_queue_guard.pop_front(); return; } @@ -1299,7 +1304,7 @@ void MavlinkFtpClient::timeout() }, [&](RenameItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout); + call_callback(item.callback, ClientResult::Timeout); work_queue_guard.pop_front(); return; } @@ -1312,7 +1317,7 @@ void MavlinkFtpClient::timeout() }, [&](CreateDirItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout); + call_callback(item.callback, ClientResult::Timeout); work_queue_guard.pop_front(); return; } @@ -1325,7 +1330,7 @@ void MavlinkFtpClient::timeout() }, [&](RemoveDirItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout); + call_callback(item.callback, ClientResult::Timeout); work_queue_guard.pop_front(); return; } @@ -1338,7 +1343,7 @@ void MavlinkFtpClient::timeout() }, [&](CompareFilesItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout, false); + call_callback(item.callback, ClientResult::Timeout, false); work_queue_guard.pop_front(); return; } @@ -1351,7 +1356,7 @@ void MavlinkFtpClient::timeout() }, [&](ListDirItem& item) { if (--work->retries == 0) { - item.callback(ClientResult::Timeout, {}); + call_callback(item.callback, ClientResult::Timeout, {}); work_queue_guard.pop_front(); return; } @@ -1445,4 +1450,22 @@ std::ostream& operator<<(std::ostream& str, MavlinkFtpClient::ClientResult const } } +template +void MavlinkFtpClient::call_callback( + const CallbackT& callback, + MavlinkFtpClient::ClientResult result, + const typename CallbackT::second_argument_type& extra_arg) +{ + _system_impl.call_user_callback( + [temp_callback = callback, temp_result = result, temp_extra_arg = extra_arg]() { + temp_callback(temp_result, temp_extra_arg); + }); +} +template +void MavlinkFtpClient::call_callback( + const CallbackT& callback, MavlinkFtpClient::ClientResult result) +{ + _system_impl.call_user_callback( + [temp_callback = callback, temp_result = result]() { temp_callback(temp_result); }); +} } // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_ftp_client.h b/src/mavsdk/core/mavlink_ftp_client.h index 20919c917b..be500a21b9 100644 --- a/src/mavsdk/core/mavlink_ftp_client.h +++ b/src/mavsdk/core/mavlink_ftp_client.h @@ -296,6 +296,13 @@ class MavlinkFtpClient { bool list_dir_start(Work& work, ListDirItem& item); bool list_dir_continue(Work& work, ListDirItem& item, PayloadHeader* payload); + template void call_callback(const CallbackT& callback, ClientResult result); + template + void call_callback( + const CallbackT& callback, + ClientResult result, + const typename CallbackT::second_argument_type& extra_arg); + static ClientResult result_from_nak(PayloadHeader* payload); void timeout(); From 8177a3c415be2610de4412ec75cce2a5c14e8763 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 11 Apr 2024 14:18:15 +0200 Subject: [PATCH 12/15] component_metadata: update proto files --- .../component_metadata/component_metadata.cpp | 118 +- .../component_metadata/component_metadata.h | 161 +- .../component_metadata_server.cpp | 38 +- .../component_metadata_server.h | 51 +- .../component_metadata.grpc.pb.cc | 209 ++ .../component_metadata.grpc.pb.h | 748 +++++ .../component_metadata.pb.cc | 2147 +++++++++++++ .../component_metadata.pb.h | 2754 +++++++++++++++++ .../component_metadata_server.grpc.pb.cc | 90 + .../component_metadata_server.grpc.pb.h | 251 ++ .../component_metadata_server.pb.cc | 644 ++++ .../component_metadata_server.pb.h | 812 +++++ src/mavsdk_server/src/grpc_server.cpp | 16 +- src/mavsdk_server/src/grpc_server.h | 36 +- .../component_metadata_service_impl.h | 339 ++ .../component_metadata_server_service_impl.h | 156 + 16 files changed, 8509 insertions(+), 61 deletions(-) create mode 100644 src/mavsdk_server/src/generated/component_metadata/component_metadata.grpc.pb.cc create mode 100644 src/mavsdk_server/src/generated/component_metadata/component_metadata.grpc.pb.h create mode 100644 src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.cc create mode 100644 src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.h create mode 100644 src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.grpc.pb.cc create mode 100644 src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.grpc.pb.h create mode 100644 src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.pb.cc create mode 100644 src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.pb.h create mode 100644 src/mavsdk_server/src/plugins/component_metadata/component_metadata_service_impl.h create mode 100644 src/mavsdk_server/src/plugins/component_metadata_server/component_metadata_server_service_impl.h diff --git a/src/mavsdk/plugins/component_metadata/component_metadata.cpp b/src/mavsdk/plugins/component_metadata/component_metadata.cpp index 9eac6a97d0..90fc8301fb 100644 --- a/src/mavsdk/plugins/component_metadata/component_metadata.cpp +++ b/src/mavsdk/plugins/component_metadata/component_metadata.cpp @@ -10,27 +10,123 @@ namespace mavsdk { -ComponentMetadata::ComponentMetadata(System& system, std::vector components_to_request) : +using MetadataData = ComponentMetadata::MetadataData; + +using MetadataUpdate = ComponentMetadata::MetadataUpdate; + +ComponentMetadata::ComponentMetadata(System& system) : PluginBase(), - _impl{std::make_unique(system, std::move(components_to_request))} + _impl{std::make_unique(system)} {} -ComponentMetadata::ComponentMetadata( - std::shared_ptr system, std::vector components_to_request) : +ComponentMetadata::ComponentMetadata(std::shared_ptr system) : PluginBase(), - _impl{std::make_unique(system, std::move(components_to_request))} + _impl{std::make_unique(system)} {} ComponentMetadata::~ComponentMetadata() {} -std::pair -ComponentMetadata::get_metadata(ComponentMetadata::MetadataType type, uint32_t compid) + +void ComponentMetadata::request_component(uint32_t compid) const +{ + _impl->request_component(compid); +} + +void ComponentMetadata::request_autopilot_component() const +{ + _impl->request_autopilot_component(); +} + +ComponentMetadata::MetadataAvailableHandle +ComponentMetadata::subscribe_metadata_available(const MetadataAvailableCallback& callback) +{ + return _impl->subscribe_metadata_available(callback); +} + +void ComponentMetadata::unsubscribe_metadata_available(MetadataAvailableHandle handle) { - return _impl->get_metadata(type, compid); + _impl->unsubscribe_metadata_available(handle); } -void ComponentMetadata::register_notification_callback( - const ComponentMetadata::NotificationCallback& callback) + +std::pair +ComponentMetadata::get_metadata(uint32_t compid, MetadataType metadata_type) const +{ + return _impl->get_metadata(compid, metadata_type); +} + +bool operator==( + const ComponentMetadata::MetadataData& lhs, const ComponentMetadata::MetadataData& rhs) +{ + return (rhs.json_metadata == lhs.json_metadata); +} + +std::ostream& operator<<(std::ostream& str, ComponentMetadata::MetadataData const& metadata_data) +{ + str << std::setprecision(15); + str << "metadata_data:" << '\n' << "{\n"; + str << " json_metadata: " << metadata_data.json_metadata << '\n'; + str << '}'; + return str; +} + +std::ostream& operator<<(std::ostream& str, ComponentMetadata::Result const& result) +{ + switch (result) { + case ComponentMetadata::Result::Success: + return str << "Success"; + case ComponentMetadata::Result::NotAvailable: + return str << "Not Available"; + case ComponentMetadata::Result::ConnectionError: + return str << "Connection Error"; + case ComponentMetadata::Result::Unsupported: + return str << "Unsupported"; + case ComponentMetadata::Result::Denied: + return str << "Denied"; + case ComponentMetadata::Result::Failed: + return str << "Failed"; + case ComponentMetadata::Result::Timeout: + return str << "Timeout"; + case ComponentMetadata::Result::NoSystem: + return str << "No System"; + case ComponentMetadata::Result::NotRequested: + return str << "Not Requested"; + default: + return str << "Unknown"; + } +} + +bool operator==( + const ComponentMetadata::MetadataUpdate& lhs, const ComponentMetadata::MetadataUpdate& rhs) +{ + return (rhs.compid == lhs.compid) && (rhs.type == lhs.type) && + (rhs.json_metadata == lhs.json_metadata); +} + +std::ostream& +operator<<(std::ostream& str, ComponentMetadata::MetadataUpdate const& metadata_update) +{ + str << std::setprecision(15); + str << "metadata_update:" << '\n' << "{\n"; + str << " compid: " << metadata_update.compid << '\n'; + str << " type: " << metadata_update.type << '\n'; + str << " json_metadata: " << metadata_update.json_metadata << '\n'; + str << '}'; + return str; +} + +std::ostream& operator<<(std::ostream& str, ComponentMetadata::MetadataType const& metadata_type) { - _impl->register_notification_callback(callback); + switch (metadata_type) { + case ComponentMetadata::MetadataType::AllCompleted: + return str << "All Completed"; + case ComponentMetadata::MetadataType::Parameter: + return str << "Parameter"; + case ComponentMetadata::MetadataType::Events: + return str << "Events"; + case ComponentMetadata::MetadataType::Actuators: + return str << "Actuators"; + default: + return str << "Unknown"; + } } } // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h b/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h index 4a5d038d08..19be566c0e 100644 --- a/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h +++ b/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h @@ -14,7 +14,6 @@ #include #include -#include "mavlink_include.h" #include "plugin_base.h" #include "handle.h" @@ -25,7 +24,7 @@ class System; class ComponentMetadataImpl; /** - * @brief Access component metadata such as parameters. + * @brief Access component metadata json definitions, such as parameters. */ class ComponentMetadata : public PluginBase { public: @@ -40,9 +39,7 @@ class ComponentMetadata : public PluginBase { * * @param system The specific system associated with this plugin. */ - explicit ComponentMetadata( - System& system, - std::vector components_to_request = {MAV_COMP_ID_AUTOPILOT1}); // deprecated + explicit ComponentMetadata(System& system); // deprecated /** * @brief Constructor. Creates the plugin for a specific System. @@ -55,32 +52,164 @@ class ComponentMetadata : public PluginBase { * * @param system The specific system associated with this plugin. */ - explicit ComponentMetadata( - std::shared_ptr system, - std::vector components_to_request = {MAV_COMP_ID_AUTOPILOT1}); // new + explicit ComponentMetadata(std::shared_ptr system); // new /** * @brief Destructor (internal use only). */ ~ComponentMetadata() override; + /** + * @brief + */ enum class MetadataType { - Parameter, - Events, - Actuators, + 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. */ }; - std::pair get_metadata(MetadataType type, uint32_t compid); + /** + * @brief Stream operator to print information about a `ComponentMetadata::MetadataType`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, ComponentMetadata::MetadataType const& metadata_type); - using NotificationCallback = - std::function; + /** + * @brief Metadata response + */ + struct MetadataData { + std::string json_metadata{}; /**< @brief The JSON metadata */ + }; - void register_notification_callback(const NotificationCallback& callback); + /** + * @brief Equal operator to compare two `ComponentMetadata::MetadataData` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==( + const ComponentMetadata::MetadataData& lhs, const ComponentMetadata::MetadataData& rhs); + + /** + * @brief Stream operator to print information about a `ComponentMetadata::MetadataData`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, ComponentMetadata::MetadataData const& metadata_data); + + /** + * @brief Possible results returned for GetMetadata + */ + enum class Result { + Success, /**< @brief. */ + NotAvailable, /**< @brief. */ + ConnectionError, /**< @brief. */ + Unsupported, /**< @brief. */ + Denied, /**< @brief. */ + Failed, /**< @brief. */ + Timeout, /**< @brief. */ + NoSystem, /**< @brief. */ + NotRequested, /**< @brief. */ + }; + + /** + * @brief Stream operator to print information about a `ComponentMetadata::Result`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, ComponentMetadata::Result const& result); + + /** + * @brief Metadata for a given component and type + */ + struct MetadataUpdate { + uint32_t compid{}; /**< @brief The component ID */ + MetadataType type{}; /**< @brief The metadata type */ + std::string json_metadata{}; /**< @brief The JSON metadata */ + }; + + /** + * @brief Equal operator to compare two `ComponentMetadata::MetadataUpdate` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==( + const ComponentMetadata::MetadataUpdate& lhs, const ComponentMetadata::MetadataUpdate& rhs); + + /** + * @brief Stream operator to print information about a `ComponentMetadata::MetadataUpdate`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, ComponentMetadata::MetadataUpdate const& metadata_update); + + /** + * @brief Callback type for asynchronous ComponentMetadata calls. + */ + using ResultCallback = std::function; + + /** + * @brief Request metadata from a specific component. This is used to start requesting metadata + * from a component. The metadata can later be accessed via subscription (see below) or + * GetMetadata. + * + * This function is blocking. + * + * @return Result of request. + */ + void request_component(uint32_t compid) const; + + /** + * @brief Request metadata from the autopilot component. This is used to start requesting + * metadata from the autopilot. The metadata can later be accessed via subscription (see below) + * or GetMetadata. + * + * This function is blocking. + * + * @return Result of request. + */ + void request_autopilot_component() const; + + /** + * @brief Callback type for subscribe_metadata_available. + */ + using MetadataAvailableCallback = std::function; + + /** + * @brief Handle type for subscribe_metadata_available. + */ + using MetadataAvailableHandle = Handle; + + /** + * @brief Register a callback that gets called when metadata is available + */ + MetadataAvailableHandle subscribe_metadata_available(const MetadataAvailableCallback& callback); + + /** + * @brief Unsubscribe from subscribe_metadata_available + */ + void unsubscribe_metadata_available(MetadataAvailableHandle handle); + + /** + * @brief Access metadata. This can be used if you know the metadata is available already, + * otherwise use the subscription to get notified when it becomes available. + * + * This function is blocking. + * + * @return Result of request. + */ + std::pair + get_metadata(uint32_t compid, MetadataType metadata_type) const; /** * @brief Copy constructor. */ - ComponentMetadata(const ComponentMetadata& other) = delete; + ComponentMetadata(const ComponentMetadata& other); /** * @brief Equality operator (object is not copyable). diff --git a/src/mavsdk/plugins/component_metadata_server/component_metadata_server.cpp b/src/mavsdk/plugins/component_metadata_server/component_metadata_server.cpp index 803bf3ff17..497f033103 100644 --- a/src/mavsdk/plugins/component_metadata_server/component_metadata_server.cpp +++ b/src/mavsdk/plugins/component_metadata_server/component_metadata_server.cpp @@ -3,11 +3,15 @@ // (see // https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/component_metadata_server/component_metadata_server.proto) +#include + #include "component_metadata_server_impl.h" #include "plugins/component_metadata_server/component_metadata_server.h" namespace mavsdk { +using Metadata = ComponentMetadataServer::Metadata; + ComponentMetadataServer::ComponentMetadataServer( std::shared_ptr server_component) : ServerPluginBase(), @@ -15,9 +19,41 @@ ComponentMetadataServer::ComponentMetadataServer( {} ComponentMetadataServer::~ComponentMetadataServer() {} -void ComponentMetadataServer::set_metadata(const std::vector& metadata) + +void ComponentMetadataServer::set_metadata(std::vector metadata) const { _impl->set_metadata(metadata); } +bool operator==( + const ComponentMetadataServer::Metadata& lhs, const ComponentMetadataServer::Metadata& rhs) +{ + return (rhs.type == lhs.type) && (rhs.json_metadata == lhs.json_metadata); +} + +std::ostream& operator<<(std::ostream& str, ComponentMetadataServer::Metadata const& metadata) +{ + str << std::setprecision(15); + str << "metadata:" << '\n' << "{\n"; + str << " type: " << metadata.type << '\n'; + str << " json_metadata: " << metadata.json_metadata << '\n'; + str << '}'; + return str; +} + +std::ostream& +operator<<(std::ostream& str, ComponentMetadataServer::MetadataType const& metadata_type) +{ + switch (metadata_type) { + case ComponentMetadataServer::MetadataType::Parameter: + return str << "Parameter"; + case ComponentMetadataServer::MetadataType::Events: + return str << "Events"; + case ComponentMetadataServer::MetadataType::Actuators: + return str << "Actuators"; + default: + return str << "Unknown"; + } +} + } // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h b/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h index 36ed76c8c0..eed0a64122 100644 --- a/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h +++ b/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h @@ -24,7 +24,7 @@ class ServerComponent; class ComponentMetadataServerImpl; /** - * @brief Provide component metadata such as parameters. + * @brief Provide component metadata json definitions, such as parameters. */ class ComponentMetadataServer : public ServerPluginBase { public: @@ -46,18 +46,55 @@ class ComponentMetadataServer : public ServerPluginBase { */ ~ComponentMetadataServer() override; + /** + * @brief + */ enum class MetadataType { - Parameter, - Events, - Actuators, + Parameter, /**< @brief Parameter metadata. */ + Events, /**< @brief Event definitions. */ + Actuators, /**< @brief Actuator definitions. */ }; + /** + * @brief Stream operator to print information about a `ComponentMetadataServer::MetadataType`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, ComponentMetadataServer::MetadataType const& metadata_type); + + /** + * @brief + */ struct Metadata { - MetadataType type; - std::string json_data; + MetadataType type{}; /**< @brief The metadata type */ + std::string json_metadata{}; /**< @brief The JSON metadata */ }; - void set_metadata(const std::vector& metadata); + /** + * @brief Equal operator to compare two `ComponentMetadataServer::Metadata` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==( + const ComponentMetadataServer::Metadata& lhs, const ComponentMetadataServer::Metadata& rhs); + + /** + * @brief Stream operator to print information about a `ComponentMetadataServer::Metadata`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, ComponentMetadataServer::Metadata const& metadata); + + /** + * @brief Provide metadata (can only be called once) + * + * This function is blocking. + * + * @return Result of request. + */ + void set_metadata(std::vector metadata) const; /** * @brief Copy constructor. diff --git a/src/mavsdk_server/src/generated/component_metadata/component_metadata.grpc.pb.cc b/src/mavsdk_server/src/generated/component_metadata/component_metadata.grpc.pb.cc new file mode 100644 index 0000000000..84c3d1b87d --- /dev/null +++ b/src/mavsdk_server/src/generated/component_metadata/component_metadata.grpc.pb.cc @@ -0,0 +1,209 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: component_metadata/component_metadata.proto + +#include "component_metadata/component_metadata.pb.h" +#include "component_metadata/component_metadata.grpc.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +namespace mavsdk { +namespace rpc { +namespace component_metadata { + +static const char* ComponentMetadataService_method_names[] = { + "/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestComponent", + "/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestAutopilotComponent", + "/mavsdk.rpc.component_metadata.ComponentMetadataService/SubscribeMetadataAvailable", + "/mavsdk.rpc.component_metadata.ComponentMetadataService/GetMetadata", +}; + +std::unique_ptr< ComponentMetadataService::Stub> ComponentMetadataService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { + (void)options; + std::unique_ptr< ComponentMetadataService::Stub> stub(new ComponentMetadataService::Stub(channel, options)); + return stub; +} + +ComponentMetadataService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) + : channel_(channel), rpcmethod_RequestComponent_(ComponentMetadataService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_RequestAutopilotComponent_(ComponentMetadataService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeMetadataAvailable_(ComponentMetadataService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_GetMetadata_(ComponentMetadataService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + {} + +::grpc::Status ComponentMetadataService::Stub::RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::mavsdk::rpc::component_metadata::RequestComponentResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RequestComponent_, context, request, response); +} + +void ComponentMetadataService::Stub::async::RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::mavsdk::rpc::component_metadata::RequestComponentResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RequestComponent_, context, request, response, std::move(f)); +} + +void ComponentMetadataService::Stub::async::RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RequestComponent_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestComponentResponse>* ComponentMetadataService::Stub::PrepareAsyncRequestComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::component_metadata::RequestComponentResponse, ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RequestComponent_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestComponentResponse>* ComponentMetadataService::Stub::AsyncRequestComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRequestComponentRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status ComponentMetadataService::Stub::RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RequestAutopilotComponent_, context, request, response); +} + +void ComponentMetadataService::Stub::async::RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RequestAutopilotComponent_, context, request, response, std::move(f)); +} + +void ComponentMetadataService::Stub::async::RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RequestAutopilotComponent_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* ComponentMetadataService::Stub::PrepareAsyncRequestAutopilotComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RequestAutopilotComponent_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* ComponentMetadataService::Stub::AsyncRequestAutopilotComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRequestAutopilotComponentRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::ClientReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* ComponentMetadataService::Stub::SubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>::Create(channel_.get(), rpcmethod_SubscribeMetadataAvailable_, context, request); +} + +void ComponentMetadataService::Stub::async::SubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeMetadataAvailable_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* ComponentMetadataService::Stub::AsyncSubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeMetadataAvailable_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* ComponentMetadataService::Stub::PrepareAsyncSubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeMetadataAvailable_, context, request, false, nullptr); +} + +::grpc::Status ComponentMetadataService::Stub::GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::mavsdk::rpc::component_metadata::GetMetadataResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetMetadata_, context, request, response); +} + +void ComponentMetadataService::Stub::async::GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::mavsdk::rpc::component_metadata::GetMetadataResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetMetadata_, context, request, response, std::move(f)); +} + +void ComponentMetadataService::Stub::async::GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetMetadata_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::GetMetadataResponse>* ComponentMetadataService::Stub::PrepareAsyncGetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::component_metadata::GetMetadataResponse, ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetMetadata_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::GetMetadataResponse>* ComponentMetadataService::Stub::AsyncGetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetMetadataRaw(context, request, cq); + result->StartCall(); + return result; +} + +ComponentMetadataService::Service::Service() { + AddMethod(new ::grpc::internal::RpcServiceMethod( + ComponentMetadataService_method_names[0], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< ComponentMetadataService::Service, ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::mavsdk::rpc::component_metadata::RequestComponentResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](ComponentMetadataService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::component_metadata::RequestComponentRequest* req, + ::mavsdk::rpc::component_metadata::RequestComponentResponse* resp) { + return service->RequestComponent(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + ComponentMetadataService_method_names[1], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< ComponentMetadataService::Service, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](ComponentMetadataService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* req, + ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* resp) { + return service->RequestAutopilotComponent(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + ComponentMetadataService_method_names[2], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< ComponentMetadataService::Service, ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest, ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>( + [](ComponentMetadataService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* writer) { + return service->SubscribeMetadataAvailable(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + ComponentMetadataService_method_names[3], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< ComponentMetadataService::Service, ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::mavsdk::rpc::component_metadata::GetMetadataResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](ComponentMetadataService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::component_metadata::GetMetadataRequest* req, + ::mavsdk::rpc::component_metadata::GetMetadataResponse* resp) { + return service->GetMetadata(ctx, req, resp); + }, this))); +} + +ComponentMetadataService::Service::~Service() { +} + +::grpc::Status ComponentMetadataService::Service::RequestComponent(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status ComponentMetadataService::Service::RequestAutopilotComponent(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status ComponentMetadataService::Service::SubscribeMetadataAvailable(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status ComponentMetadataService::Service::GetMetadata(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + + +} // namespace mavsdk +} // namespace rpc +} // namespace component_metadata + diff --git a/src/mavsdk_server/src/generated/component_metadata/component_metadata.grpc.pb.h b/src/mavsdk_server/src/generated/component_metadata/component_metadata.grpc.pb.h new file mode 100644 index 0000000000..98686a85ba --- /dev/null +++ b/src/mavsdk_server/src/generated/component_metadata/component_metadata.grpc.pb.h @@ -0,0 +1,748 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: component_metadata/component_metadata.proto +#ifndef GRPC_component_5fmetadata_2fcomponent_5fmetadata_2eproto__INCLUDED +#define GRPC_component_5fmetadata_2fcomponent_5fmetadata_2eproto__INCLUDED + +#include "component_metadata/component_metadata.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 component_metadata { + +// Access component metadata json definitions, such as parameters. +class ComponentMetadataService final { + public: + static constexpr char const* service_full_name() { + return "mavsdk.rpc.component_metadata.ComponentMetadataService"; + } + class StubInterface { + public: + virtual ~StubInterface() {} + // + // Request metadata from a specific component. This is used to start requesting metadata from a component. + // The metadata can later be accessed via subscription (see below) or GetMetadata. + virtual ::grpc::Status RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestComponentResponse>> AsyncRequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestComponentResponse>>(AsyncRequestComponentRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestComponentResponse>> PrepareAsyncRequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestComponentResponse>>(PrepareAsyncRequestComponentRaw(context, request, cq)); + } + // + // Request metadata from the autopilot component. This is used to start requesting metadata from the autopilot. + // The metadata can later be accessed via subscription (see below) or GetMetadata. + virtual ::grpc::Status RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>> AsyncRequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>>(AsyncRequestAutopilotComponentRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>> PrepareAsyncRequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>>(PrepareAsyncRequestAutopilotComponentRaw(context, request, cq)); + } + // + // Register a callback that gets called when metadata is available + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>> SubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>>(SubscribeMetadataAvailableRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>> AsyncSubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>>(AsyncSubscribeMetadataAvailableRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>> PrepareAsyncSubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>>(PrepareAsyncSubscribeMetadataAvailableRaw(context, request, cq)); + } + // + // Access metadata. This can be used if you know the metadata is available already, otherwise use + // the subscription to get notified when it becomes available. + virtual ::grpc::Status GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::GetMetadataResponse>> AsyncGetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::GetMetadataResponse>>(AsyncGetMetadataRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::GetMetadataResponse>> PrepareAsyncGetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::GetMetadataResponse>>(PrepareAsyncGetMetadataRaw(context, request, cq)); + } + class async_interface { + public: + virtual ~async_interface() {} + // + // Request metadata from a specific component. This is used to start requesting metadata from a component. + // The metadata can later be accessed via subscription (see below) or GetMetadata. + virtual void RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response, std::function) = 0; + virtual void RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Request metadata from the autopilot component. This is used to start requesting metadata from the autopilot. + // The metadata can later be accessed via subscription (see below) or GetMetadata. + virtual void RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response, std::function) = 0; + virtual void RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Register a callback that gets called when metadata is available + virtual void SubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* reactor) = 0; + // + // Access metadata. This can be used if you know the metadata is available already, otherwise use + // the subscription to get notified when it becomes available. + virtual void GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response, std::function) = 0; + virtual void GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + }; + typedef class async_interface experimental_async_interface; + virtual class async_interface* async() { return nullptr; } + class async_interface* experimental_async() { return async(); } + private: + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestComponentResponse>* AsyncRequestComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestComponentResponse>* PrepareAsyncRequestComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* AsyncRequestAutopilotComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* PrepareAsyncRequestAutopilotComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* SubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* AsyncSubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* PrepareAsyncSubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::GetMetadataResponse>* AsyncGetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata::GetMetadataResponse>* PrepareAsyncGetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) = 0; + }; + class Stub final : public StubInterface { + public: + Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + ::grpc::Status RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestComponentResponse>> AsyncRequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestComponentResponse>>(AsyncRequestComponentRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestComponentResponse>> PrepareAsyncRequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestComponentResponse>>(PrepareAsyncRequestComponentRaw(context, request, cq)); + } + ::grpc::Status RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>> AsyncRequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>>(AsyncRequestAutopilotComponentRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>> PrepareAsyncRequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>>(PrepareAsyncRequestAutopilotComponentRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>> SubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>>(SubscribeMetadataAvailableRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>> AsyncSubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>>(AsyncSubscribeMetadataAvailableRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>> PrepareAsyncSubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>>(PrepareAsyncSubscribeMetadataAvailableRaw(context, request, cq)); + } + ::grpc::Status GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::GetMetadataResponse>> AsyncGetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::GetMetadataResponse>>(AsyncGetMetadataRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::GetMetadataResponse>> PrepareAsyncGetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::GetMetadataResponse>>(PrepareAsyncGetMetadataRaw(context, request, cq)); + } + class async final : + public StubInterface::async_interface { + public: + void RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response, std::function) override; + void RequestComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response, std::function) override; + void RequestAutopilotComponent(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeMetadataAvailable(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* reactor) override; + void GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response, std::function) override; + void GetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + private: + friend class Stub; + explicit async(Stub* stub): stub_(stub) { } + Stub* stub() { return stub_; } + Stub* stub_; + }; + class async* async() override { return &async_stub_; } + + private: + std::shared_ptr< ::grpc::ChannelInterface> channel_; + class async async_stub_{this}; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestComponentResponse>* AsyncRequestComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestComponentResponse>* PrepareAsyncRequestComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* AsyncRequestAutopilotComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* PrepareAsyncRequestAutopilotComponentRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* SubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* AsyncSubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* PrepareAsyncSubscribeMetadataAvailableRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::GetMetadataResponse>* AsyncGetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata::GetMetadataResponse>* PrepareAsyncGetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest& request, ::grpc::CompletionQueue* cq) override; + const ::grpc::internal::RpcMethod rpcmethod_RequestComponent_; + const ::grpc::internal::RpcMethod rpcmethod_RequestAutopilotComponent_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeMetadataAvailable_; + const ::grpc::internal::RpcMethod rpcmethod_GetMetadata_; + }; + 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(); + // + // Request metadata from a specific component. This is used to start requesting metadata from a component. + // The metadata can later be accessed via subscription (see below) or GetMetadata. + virtual ::grpc::Status RequestComponent(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response); + // + // Request metadata from the autopilot component. This is used to start requesting metadata from the autopilot. + // The metadata can later be accessed via subscription (see below) or GetMetadata. + virtual ::grpc::Status RequestAutopilotComponent(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response); + // + // Register a callback that gets called when metadata is available + virtual ::grpc::Status SubscribeMetadataAvailable(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* writer); + // + // Access metadata. This can be used if you know the metadata is available already, otherwise use + // the subscription to get notified when it becomes available. + virtual ::grpc::Status GetMetadata(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response); + }; + template + class WithAsyncMethod_RequestComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RequestComponent() { + ::grpc::Service::MarkMethodAsync(0); + } + ~WithAsyncMethod_RequestComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRequestComponent(::grpc::ServerContext* context, ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::component_metadata::RequestComponentResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RequestAutopilotComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RequestAutopilotComponent() { + ::grpc::Service::MarkMethodAsync(1); + } + ~WithAsyncMethod_RequestAutopilotComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestAutopilotComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRequestAutopilotComponent(::grpc::ServerContext* context, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeMetadataAvailable : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeMetadataAvailable() { + ::grpc::Service::MarkMethodAsync(2); + } + ~WithAsyncMethod_SubscribeMetadataAvailable() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeMetadataAvailable(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeMetadataAvailable(::grpc::ServerContext* context, ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(2, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_GetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_GetMetadata() { + ::grpc::Service::MarkMethodAsync(3); + } + ~WithAsyncMethod_GetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata::GetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetMetadata(::grpc::ServerContext* context, ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::component_metadata::GetMetadataResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_RequestComponent > > > AsyncService; + template + class WithCallbackMethod_RequestComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RequestComponent() { + ::grpc::Service::MarkMethodCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::mavsdk::rpc::component_metadata::RequestComponentResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestComponentResponse* response) { return this->RequestComponent(context, request, response); }));} + void SetMessageAllocatorFor_RequestComponent( + ::grpc::MessageAllocator< ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::mavsdk::rpc::component_metadata::RequestComponentResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::mavsdk::rpc::component_metadata::RequestComponentResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RequestComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RequestComponent( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestComponentResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_RequestAutopilotComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RequestAutopilotComponent() { + ::grpc::Service::MarkMethodCallback(1, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* request, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* response) { return this->RequestAutopilotComponent(context, request, response); }));} + void SetMessageAllocatorFor_RequestAutopilotComponent( + ::grpc::MessageAllocator< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RequestAutopilotComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestAutopilotComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RequestAutopilotComponent( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeMetadataAvailable : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeMetadataAvailable() { + ::grpc::Service::MarkMethodCallback(2, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest, ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* request) { return this->SubscribeMetadataAvailable(context, request); })); + } + ~WithCallbackMethod_SubscribeMetadataAvailable() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeMetadataAvailable(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* SubscribeMetadataAvailable( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_GetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_GetMetadata() { + ::grpc::Service::MarkMethodCallback(3, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::mavsdk::rpc::component_metadata::GetMetadataResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* request, ::mavsdk::rpc::component_metadata::GetMetadataResponse* response) { return this->GetMetadata(context, request, response); }));} + void SetMessageAllocatorFor_GetMetadata( + ::grpc::MessageAllocator< ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::mavsdk::rpc::component_metadata::GetMetadataResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::mavsdk::rpc::component_metadata::GetMetadataResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_GetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata::GetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetMetadata( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata::GetMetadataResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_RequestComponent > > > CallbackService; + typedef CallbackService ExperimentalCallbackService; + template + class WithGenericMethod_RequestComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RequestComponent() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_RequestComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_RequestAutopilotComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RequestAutopilotComponent() { + ::grpc::Service::MarkMethodGeneric(1); + } + ~WithGenericMethod_RequestAutopilotComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestAutopilotComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeMetadataAvailable : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeMetadataAvailable() { + ::grpc::Service::MarkMethodGeneric(2); + } + ~WithGenericMethod_SubscribeMetadataAvailable() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeMetadataAvailable(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_GetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_GetMetadata() { + ::grpc::Service::MarkMethodGeneric(3); + } + ~WithGenericMethod_GetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata::GetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithRawMethod_RequestComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RequestComponent() { + ::grpc::Service::MarkMethodRaw(0); + } + ~WithRawMethod_RequestComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRequestComponent(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RequestAutopilotComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RequestAutopilotComponent() { + ::grpc::Service::MarkMethodRaw(1); + } + ~WithRawMethod_RequestAutopilotComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestAutopilotComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRequestAutopilotComponent(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeMetadataAvailable : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeMetadataAvailable() { + ::grpc::Service::MarkMethodRaw(2); + } + ~WithRawMethod_SubscribeMetadataAvailable() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeMetadataAvailable(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeMetadataAvailable(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(2, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_GetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetMetadata() { + ::grpc::Service::MarkMethodRaw(3); + } + ~WithRawMethod_GetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata::GetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetMetadata(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawCallbackMethod_RequestComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RequestComponent() { + ::grpc::Service::MarkMethodRawCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RequestComponent(context, request, response); })); + } + ~WithRawCallbackMethod_RequestComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RequestComponent( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_RequestAutopilotComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RequestAutopilotComponent() { + ::grpc::Service::MarkMethodRawCallback(1, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RequestAutopilotComponent(context, request, response); })); + } + ~WithRawCallbackMethod_RequestAutopilotComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RequestAutopilotComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RequestAutopilotComponent( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeMetadataAvailable : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeMetadataAvailable() { + ::grpc::Service::MarkMethodRawCallback(2, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeMetadataAvailable(context, request); })); + } + ~WithRawCallbackMethod_SubscribeMetadataAvailable() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeMetadataAvailable(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeMetadataAvailable( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_GetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetMetadata() { + ::grpc::Service::MarkMethodRawCallback(3, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetMetadata(context, request, response); })); + } + ~WithRawCallbackMethod_GetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata::GetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetMetadata( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithStreamedUnaryMethod_RequestComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RequestComponent() { + ::grpc::Service::MarkMethodStreamed(0, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::mavsdk::rpc::component_metadata::RequestComponentResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::component_metadata::RequestComponentRequest, ::mavsdk::rpc::component_metadata::RequestComponentResponse>* streamer) { + return this->StreamedRequestComponent(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RequestComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RequestComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRequestComponent(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::component_metadata::RequestComponentRequest,::mavsdk::rpc::component_metadata::RequestComponentResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RequestAutopilotComponent : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RequestAutopilotComponent() { + ::grpc::Service::MarkMethodStreamed(1, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* streamer) { + return this->StreamedRequestAutopilotComponent(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RequestAutopilotComponent() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RequestAutopilotComponent(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest* /*request*/, ::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRequestAutopilotComponent(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest,::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_GetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetMetadata() { + ::grpc::Service::MarkMethodStreamed(3, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::mavsdk::rpc::component_metadata::GetMetadataResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::component_metadata::GetMetadataRequest, ::mavsdk::rpc::component_metadata::GetMetadataResponse>* streamer) { + return this->StreamedGetMetadata(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::GetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata::GetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetMetadata(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::component_metadata::GetMetadataRequest,::mavsdk::rpc::component_metadata::GetMetadataResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_RequestComponent > > StreamedUnaryService; + template + class WithSplitStreamingMethod_SubscribeMetadataAvailable : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeMetadataAvailable() { + ::grpc::Service::MarkMethodStreamed(2, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest, ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest, ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* streamer) { + return this->StreamedSubscribeMetadataAvailable(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeMetadataAvailable() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeMetadataAvailable(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeMetadataAvailable(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest,::mavsdk::rpc::component_metadata::MetadataAvailableResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeMetadataAvailable SplitStreamedService; + typedef WithStreamedUnaryMethod_RequestComponent > > > StreamedService; +}; + +} // namespace component_metadata +} // namespace rpc +} // namespace mavsdk + + +#endif // GRPC_component_5fmetadata_2fcomponent_5fmetadata_2eproto__INCLUDED diff --git a/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.cc b/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.cc new file mode 100644 index 0000000000..14d3d0bc4b --- /dev/null +++ b/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.cc @@ -0,0 +1,2147 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: component_metadata/component_metadata.proto + +#include "component_metadata/component_metadata.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 component_metadata { + template +PROTOBUF_CONSTEXPR SubscribeMetadataAvailableRequest::SubscribeMetadataAvailableRequest(::_pbi::ConstantInitialized) {} +struct SubscribeMetadataAvailableRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeMetadataAvailableRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeMetadataAvailableRequestDefaultTypeInternal() {} + union { + SubscribeMetadataAvailableRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeMetadataAvailableRequestDefaultTypeInternal _SubscribeMetadataAvailableRequest_default_instance_; + template +PROTOBUF_CONSTEXPR RequestComponentResponse::RequestComponentResponse(::_pbi::ConstantInitialized) {} +struct RequestComponentResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RequestComponentResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RequestComponentResponseDefaultTypeInternal() {} + union { + RequestComponentResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RequestComponentResponseDefaultTypeInternal _RequestComponentResponse_default_instance_; + +inline constexpr RequestComponentRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : compid_{0u}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR RequestComponentRequest::RequestComponentRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct RequestComponentRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RequestComponentRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RequestComponentRequestDefaultTypeInternal() {} + union { + RequestComponentRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RequestComponentRequestDefaultTypeInternal _RequestComponentRequest_default_instance_; + template +PROTOBUF_CONSTEXPR RequestAutopilotComponentResponse::RequestAutopilotComponentResponse(::_pbi::ConstantInitialized) {} +struct RequestAutopilotComponentResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RequestAutopilotComponentResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RequestAutopilotComponentResponseDefaultTypeInternal() {} + union { + RequestAutopilotComponentResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RequestAutopilotComponentResponseDefaultTypeInternal _RequestAutopilotComponentResponse_default_instance_; + template +PROTOBUF_CONSTEXPR RequestAutopilotComponentRequest::RequestAutopilotComponentRequest(::_pbi::ConstantInitialized) {} +struct RequestAutopilotComponentRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RequestAutopilotComponentRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RequestAutopilotComponentRequestDefaultTypeInternal() {} + union { + RequestAutopilotComponentRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RequestAutopilotComponentRequestDefaultTypeInternal _RequestAutopilotComponentRequest_default_instance_; + +inline constexpr MetadataUpdate::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : json_metadata_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + compid_{0u}, + type_{static_cast< ::mavsdk::rpc::component_metadata::MetadataType >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR MetadataUpdate::MetadataUpdate(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct MetadataUpdateDefaultTypeInternal { + PROTOBUF_CONSTEXPR MetadataUpdateDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~MetadataUpdateDefaultTypeInternal() {} + union { + MetadataUpdate _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 MetadataUpdateDefaultTypeInternal _MetadataUpdate_default_instance_; + +inline constexpr MetadataData::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : json_metadata_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR MetadataData::MetadataData(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct MetadataDataDefaultTypeInternal { + PROTOBUF_CONSTEXPR MetadataDataDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~MetadataDataDefaultTypeInternal() {} + union { + MetadataData _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 MetadataDataDefaultTypeInternal _MetadataData_default_instance_; + +inline constexpr GetMetadataRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : compid_{0u}, + metadata_type_{static_cast< ::mavsdk::rpc::component_metadata::MetadataType >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetMetadataRequest::GetMetadataRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetMetadataRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetMetadataRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetMetadataRequestDefaultTypeInternal() {} + union { + GetMetadataRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetMetadataRequestDefaultTypeInternal _GetMetadataRequest_default_instance_; + +inline constexpr ComponentMetadataResult::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : result_str_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + result_{static_cast< ::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ComponentMetadataResult::ComponentMetadataResult(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ComponentMetadataResultDefaultTypeInternal { + PROTOBUF_CONSTEXPR ComponentMetadataResultDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ComponentMetadataResultDefaultTypeInternal() {} + union { + ComponentMetadataResult _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ComponentMetadataResultDefaultTypeInternal _ComponentMetadataResult_default_instance_; + +inline constexpr MetadataAvailableResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + data_{nullptr} {} + +template +PROTOBUF_CONSTEXPR MetadataAvailableResponse::MetadataAvailableResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct MetadataAvailableResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR MetadataAvailableResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~MetadataAvailableResponseDefaultTypeInternal() {} + union { + MetadataAvailableResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 MetadataAvailableResponseDefaultTypeInternal _MetadataAvailableResponse_default_instance_; + +inline constexpr GetMetadataResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + component_metadata_result_{nullptr}, + response_{nullptr} {} + +template +PROTOBUF_CONSTEXPR GetMetadataResponse::GetMetadataResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetMetadataResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetMetadataResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetMetadataResponseDefaultTypeInternal() {} + union { + GetMetadataResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetMetadataResponseDefaultTypeInternal _GetMetadataResponse_default_instance_; +} // namespace component_metadata +} // namespace rpc +} // namespace mavsdk +static ::_pb::Metadata file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[11]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_component_5fmetadata_2fcomponent_5fmetadata_2eproto[2]; +static constexpr const ::_pb::ServiceDescriptor** + file_level_service_descriptors_component_5fmetadata_2fcomponent_5fmetadata_2eproto = nullptr; +const ::uint32_t TableStruct_component_5fmetadata_2fcomponent_5fmetadata_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( + protodesc_cold) = { + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::RequestComponentRequest, _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::component_metadata::RequestComponentRequest, _impl_.compid_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::GetMetadataRequest, _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::component_metadata::GetMetadataRequest, _impl_.compid_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::GetMetadataRequest, _impl_.metadata_type_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::GetMetadataResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::GetMetadataResponse, _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::component_metadata::GetMetadataResponse, _impl_.component_metadata_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::GetMetadataResponse, _impl_.response_), + 0, + 1, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::MetadataData, _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::component_metadata::MetadataData, _impl_.json_metadata_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::ComponentMetadataResult, _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::component_metadata::ComponentMetadataResult, _impl_.result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::ComponentMetadataResult, _impl_.result_str_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::RequestComponentResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest, _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::component_metadata::MetadataAvailableResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::MetadataAvailableResponse, _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::component_metadata::MetadataAvailableResponse, _impl_.data_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::MetadataUpdate, _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::component_metadata::MetadataUpdate, _impl_.compid_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::MetadataUpdate, _impl_.type_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::MetadataUpdate, _impl_.json_metadata_), +}; + +static const ::_pbi::MigrationSchema + schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + {0, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestComponentRequest)}, + {9, -1, -1, sizeof(::mavsdk::rpc::component_metadata::GetMetadataRequest)}, + {19, 29, -1, sizeof(::mavsdk::rpc::component_metadata::GetMetadataResponse)}, + {31, -1, -1, sizeof(::mavsdk::rpc::component_metadata::MetadataData)}, + {40, -1, -1, sizeof(::mavsdk::rpc::component_metadata::ComponentMetadataResult)}, + {50, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestComponentResponse)}, + {58, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest)}, + {66, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse)}, + {74, -1, -1, sizeof(::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest)}, + {82, 91, -1, sizeof(::mavsdk::rpc::component_metadata::MetadataAvailableResponse)}, + {92, -1, -1, sizeof(::mavsdk::rpc::component_metadata::MetadataUpdate)}, +}; + +static const ::_pb::Message* const file_default_instances[] = { + &::mavsdk::rpc::component_metadata::_RequestComponentRequest_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_GetMetadataRequest_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_GetMetadataResponse_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_MetadataData_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_ComponentMetadataResult_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_RequestComponentResponse_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_RequestAutopilotComponentRequest_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_RequestAutopilotComponentResponse_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_SubscribeMetadataAvailableRequest_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_MetadataAvailableResponse_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_MetadataUpdate_default_instance_._instance, +}; +const char descriptor_table_protodef_component_5fmetadata_2fcomponent_5fmetadata_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + "\n+component_metadata/component_metadata." + "proto\022\035mavsdk.rpc.component_metadata\032\024ma" + "vsdk_options.proto\")\n\027RequestComponentRe" + "quest\022\016\n\006compid\030\001 \001(\r\"h\n\022GetMetadataRequ" + "est\022\016\n\006compid\030\001 \001(\r\022B\n\rmetadata_type\030\002 \001" + "(\0162+.mavsdk.rpc.component_metadata.Metad" + "ataType\"\257\001\n\023GetMetadataResponse\022Y\n\031compo" + "nent_metadata_result\030\001 \001(\01326.mavsdk.rpc." + "component_metadata.ComponentMetadataResu" + "lt\022=\n\010response\030\002 \001(\0132+.mavsdk.rpc.compon" + "ent_metadata.MetadataData\"%\n\014MetadataDat" + "a\022\025\n\rjson_metadata\030\001 \001(\t\"\324\002\n\027ComponentMe" + "tadataResult\022M\n\006result\030\001 \001(\0162=.mavsdk.rp" + "c.component_metadata.ComponentMetadataRe" + "sult.Result\022\022\n\nresult_str\030\002 \001(\t\"\325\001\n\006Resu" + "lt\022\022\n\016RESULT_SUCCESS\020\000\022\030\n\024RESULT_NOT_AVA" + "ILABLE\020\001\022\033\n\027RESULT_CONNECTION_ERROR\020\002\022\026\n" + "\022RESULT_UNSUPPORTED\020\003\022\021\n\rRESULT_DENIED\020\004" + "\022\021\n\rRESULT_FAILED\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022" + "\024\n\020RESULT_NO_SYSTEM\020\007\022\030\n\024RESULT_NOT_REQU" + "ESTED\020\010\"\032\n\030RequestComponentResponse\"\"\n R" + "equestAutopilotComponentRequest\"#\n!Reque" + "stAutopilotComponentResponse\"#\n!Subscrib" + "eMetadataAvailableRequest\"X\n\031MetadataAva" + "ilableResponse\022;\n\004data\030\001 \001(\0132-.mavsdk.rp" + "c.component_metadata.MetadataUpdate\"r\n\016M" + "etadataUpdate\022\016\n\006compid\030\001 \001(\r\0229\n\004type\030\002 " + "\001(\0162+.mavsdk.rpc.component_metadata.Meta" + "dataType\022\025\n\rjson_metadata\030\003 \001(\t*\203\001\n\014Meta" + "dataType\022\037\n\033METADATA_TYPE_ALL_COMPLETED\020" + "\000\022\033\n\027METADATA_TYPE_PARAMETER\020\001\022\030\n\024METADA" + "TA_TYPE_EVENTS\020\002\022\033\n\027METADATA_TYPE_ACTUAT" + "ORS\020\0032\354\004\n\030ComponentMetadataService\022\211\001\n\020R" + "equestComponent\0226.mavsdk.rpc.component_m" + "etadata.RequestComponentRequest\0327.mavsdk" + ".rpc.component_metadata.RequestComponent" + "Response\"\004\200\265\030\001\022\244\001\n\031RequestAutopilotCompo" + "nent\022\?.mavsdk.rpc.component_metadata.Req" + "uestAutopilotComponentRequest\032@.mavsdk.r" + "pc.component_metadata.RequestAutopilotCo" + "mponentResponse\"\004\200\265\030\001\022\240\001\n\032SubscribeMetad" + "ataAvailable\022@.mavsdk.rpc.component_meta" + "data.SubscribeMetadataAvailableRequest\0328" + ".mavsdk.rpc.component_metadata.MetadataA" + "vailableResponse\"\004\200\265\030\0000\001\022z\n\013GetMetadata\022" + "1.mavsdk.rpc.component_metadata.GetMetad" + "ataRequest\0322.mavsdk.rpc.component_metada" + "ta.GetMetadataResponse\"\004\200\265\030\001B6\n\034io.mavsd" + "k.component_metadataB\026ComponentMetadataP" + "rotob\006proto3" +}; +static const ::_pbi::DescriptorTable* const descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_deps[1] = + { + &::descriptor_table_mavsdk_5foptions_2eproto, +}; +static ::absl::once_flag descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once; +const ::_pbi::DescriptorTable descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto = { + false, + false, + 1972, + descriptor_table_protodef_component_5fmetadata_2fcomponent_5fmetadata_2eproto, + "component_metadata/component_metadata.proto", + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_deps, + 1, + 11, + schemas, + file_default_instances, + TableStruct_component_5fmetadata_2fcomponent_5fmetadata_2eproto::offsets, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto, + file_level_enum_descriptors_component_5fmetadata_2fcomponent_5fmetadata_2eproto, + file_level_service_descriptors_component_5fmetadata_2fcomponent_5fmetadata_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_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter() { + return &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +} +// Force running AddDescriptors() at dynamic initialization time. +PROTOBUF_ATTRIBUTE_INIT_PRIORITY2 +static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_component_5fmetadata_2fcomponent_5fmetadata_2eproto(&descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto); +namespace mavsdk { +namespace rpc { +namespace component_metadata { +const ::google::protobuf::EnumDescriptor* ComponentMetadataResult_Result_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto); + return file_level_enum_descriptors_component_5fmetadata_2fcomponent_5fmetadata_2eproto[0]; +} +PROTOBUF_CONSTINIT const uint32_t ComponentMetadataResult_Result_internal_data_[] = { + 589824u, 0u, }; +bool ComponentMetadataResult_Result_IsValid(int value) { + return 0 <= value && value <= 8; +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_SUCCESS; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_NOT_AVAILABLE; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_CONNECTION_ERROR; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_UNSUPPORTED; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_DENIED; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_FAILED; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_TIMEOUT; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_NO_SYSTEM; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::RESULT_NOT_REQUESTED; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::Result_MIN; +constexpr ComponentMetadataResult_Result ComponentMetadataResult::Result_MAX; +constexpr int ComponentMetadataResult::Result_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::google::protobuf::EnumDescriptor* MetadataType_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto); + return file_level_enum_descriptors_component_5fmetadata_2fcomponent_5fmetadata_2eproto[1]; +} +PROTOBUF_CONSTINIT const uint32_t MetadataType_internal_data_[] = { + 262144u, 0u, }; +bool MetadataType_IsValid(int value) { + return 0 <= value && value <= 3; +} +// =================================================================== + +class RequestComponentRequest::_Internal { + public: +}; + +RequestComponentRequest::RequestComponentRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.RequestComponentRequest) +} +RequestComponentRequest::RequestComponentRequest( + ::google::protobuf::Arena* arena, const RequestComponentRequest& from) + : RequestComponentRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE RequestComponentRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void RequestComponentRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.compid_ = {}; +} +RequestComponentRequest::~RequestComponentRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata.RequestComponentRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void RequestComponentRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void RequestComponentRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata.RequestComponentRequest) + 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_.compid_ = 0u; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* RequestComponentRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> RequestComponentRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_RequestComponentRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // uint32 compid = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(RequestComponentRequest, _impl_.compid_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(RequestComponentRequest, _impl_.compid_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // uint32 compid = 1; + {PROTOBUF_FIELD_OFFSET(RequestComponentRequest, _impl_.compid_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* RequestComponentRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata.RequestComponentRequest) + ::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); + } + + 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.component_metadata.RequestComponentRequest) + return target; +} + +::size_t RequestComponentRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata.RequestComponentRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // uint32 compid = 1; + if (this->_internal_compid() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_compid()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData RequestComponentRequest::_class_data_ = { + RequestComponentRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* RequestComponentRequest::GetClassData() const { + return &_class_data_; +} + +void RequestComponentRequest::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.component_metadata.RequestComponentRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_compid() != 0) { + _this->_internal_set_compid(from._internal_compid()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void RequestComponentRequest::CopyFrom(const RequestComponentRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata.RequestComponentRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool RequestComponentRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* RequestComponentRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void RequestComponentRequest::InternalSwap(RequestComponentRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.compid_, other->_impl_.compid_); +} + +::google::protobuf::Metadata RequestComponentRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[0]); +} +// =================================================================== + +class GetMetadataRequest::_Internal { + public: +}; + +GetMetadataRequest::GetMetadataRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.GetMetadataRequest) +} +GetMetadataRequest::GetMetadataRequest( + ::google::protobuf::Arena* arena, const GetMetadataRequest& from) + : GetMetadataRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE GetMetadataRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void GetMetadataRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, compid_), + 0, + offsetof(Impl_, metadata_type_) - + offsetof(Impl_, compid_) + + sizeof(Impl_::metadata_type_)); +} +GetMetadataRequest::~GetMetadataRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata.GetMetadataRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void GetMetadataRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void GetMetadataRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata.GetMetadataRequest) + 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; + + ::memset(&_impl_.compid_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.metadata_type_) - + reinterpret_cast(&_impl_.compid_)) + sizeof(_impl_.metadata_type_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* GetMetadataRequest::_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, 0, 2> GetMetadataRequest::_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 + &_GetMetadataRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.component_metadata.MetadataType metadata_type = 2; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetMetadataRequest, _impl_.metadata_type_), 63>(), + {16, 63, 0, PROTOBUF_FIELD_OFFSET(GetMetadataRequest, _impl_.metadata_type_)}}, + // uint32 compid = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetMetadataRequest, _impl_.compid_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetMetadataRequest, _impl_.compid_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // uint32 compid = 1; + {PROTOBUF_FIELD_OFFSET(GetMetadataRequest, _impl_.compid_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // .mavsdk.rpc.component_metadata.MetadataType metadata_type = 2; + {PROTOBUF_FIELD_OFFSET(GetMetadataRequest, _impl_.metadata_type_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* GetMetadataRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata.GetMetadataRequest) + ::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); + } + + // .mavsdk.rpc.component_metadata.MetadataType metadata_type = 2; + if (this->_internal_metadata_type() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 2, this->_internal_metadata_type(), 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.component_metadata.GetMetadataRequest) + return target; +} + +::size_t GetMetadataRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata.GetMetadataRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // uint32 compid = 1; + if (this->_internal_compid() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_compid()); + } + + // .mavsdk.rpc.component_metadata.MetadataType metadata_type = 2; + if (this->_internal_metadata_type() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_metadata_type()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData GetMetadataRequest::_class_data_ = { + GetMetadataRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* GetMetadataRequest::GetClassData() const { + return &_class_data_; +} + +void GetMetadataRequest::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.component_metadata.GetMetadataRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_compid() != 0) { + _this->_internal_set_compid(from._internal_compid()); + } + if (from._internal_metadata_type() != 0) { + _this->_internal_set_metadata_type(from._internal_metadata_type()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void GetMetadataRequest::CopyFrom(const GetMetadataRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata.GetMetadataRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool GetMetadataRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* GetMetadataRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void GetMetadataRequest::InternalSwap(GetMetadataRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(GetMetadataRequest, _impl_.metadata_type_) + + sizeof(GetMetadataRequest::_impl_.metadata_type_) + - PROTOBUF_FIELD_OFFSET(GetMetadataRequest, _impl_.compid_)>( + reinterpret_cast(&_impl_.compid_), + reinterpret_cast(&other->_impl_.compid_)); +} + +::google::protobuf::Metadata GetMetadataRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[1]); +} +// =================================================================== + +class GetMetadataResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(GetMetadataResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::component_metadata::ComponentMetadataResult& component_metadata_result(const GetMetadataResponse* msg); + static void set_has_component_metadata_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } + static const ::mavsdk::rpc::component_metadata::MetadataData& response(const GetMetadataResponse* msg); + static void set_has_response(HasBits* has_bits) { + (*has_bits)[0] |= 2u; + } +}; + +const ::mavsdk::rpc::component_metadata::ComponentMetadataResult& GetMetadataResponse::_Internal::component_metadata_result(const GetMetadataResponse* msg) { + return *msg->_impl_.component_metadata_result_; +} +const ::mavsdk::rpc::component_metadata::MetadataData& GetMetadataResponse::_Internal::response(const GetMetadataResponse* msg) { + return *msg->_impl_.response_; +} +GetMetadataResponse::GetMetadataResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.GetMetadataResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetMetadataResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +GetMetadataResponse::GetMetadataResponse( + ::google::protobuf::Arena* arena, + const GetMetadataResponse& from) + : ::google::protobuf::Message(arena) { + GetMetadataResponse* 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_.component_metadata_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::component_metadata::ComponentMetadataResult>(arena, *from._impl_.component_metadata_result_) + : nullptr; + _impl_.response_ = (cached_has_bits & 0x00000002u) + ? CreateMaybeMessage<::mavsdk::rpc::component_metadata::MetadataData>(arena, *from._impl_.response_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.GetMetadataResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetMetadataResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void GetMetadataResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, component_metadata_result_), + 0, + offsetof(Impl_, response_) - + offsetof(Impl_, component_metadata_result_) + + sizeof(Impl_::response_)); +} +GetMetadataResponse::~GetMetadataResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata.GetMetadataResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void GetMetadataResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.component_metadata_result_; + delete _impl_.response_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void GetMetadataResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata.GetMetadataResponse) + 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_.component_metadata_result_ != nullptr); + _impl_.component_metadata_result_->Clear(); + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(_impl_.response_ != nullptr); + _impl_.response_->Clear(); + } + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* GetMetadataResponse::_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> GetMetadataResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(GetMetadataResponse, _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), + &_GetMetadataResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.component_metadata.MetadataData response = 2; + {::_pbi::TcParser::FastMtS1, + {18, 1, 1, PROTOBUF_FIELD_OFFSET(GetMetadataResponse, _impl_.response_)}}, + // .mavsdk.rpc.component_metadata.ComponentMetadataResult component_metadata_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetMetadataResponse, _impl_.component_metadata_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.component_metadata.ComponentMetadataResult component_metadata_result = 1; + {PROTOBUF_FIELD_OFFSET(GetMetadataResponse, _impl_.component_metadata_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.component_metadata.MetadataData response = 2; + {PROTOBUF_FIELD_OFFSET(GetMetadataResponse, _impl_.response_), _Internal::kHasBitsOffset + 1, 1, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_metadata::ComponentMetadataResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_metadata::MetadataData>()}, + }}, {{ + }}, +}; + +::uint8_t* GetMetadataResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata.GetMetadataResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.component_metadata.ComponentMetadataResult component_metadata_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::component_metadata_result(this), + _Internal::component_metadata_result(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.component_metadata.MetadataData response = 2; + if (cached_has_bits & 0x00000002u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 2, _Internal::response(this), + _Internal::response(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.component_metadata.GetMetadataResponse) + return target; +} + +::size_t GetMetadataResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata.GetMetadataResponse) + ::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.component_metadata.ComponentMetadataResult component_metadata_result = 1; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.component_metadata_result_); + } + + // .mavsdk.rpc.component_metadata.MetadataData response = 2; + if (cached_has_bits & 0x00000002u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.response_); + } + + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData GetMetadataResponse::_class_data_ = { + GetMetadataResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* GetMetadataResponse::GetClassData() const { + return &_class_data_; +} + +void GetMetadataResponse::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.component_metadata.GetMetadataResponse) + 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_component_metadata_result()->::mavsdk::rpc::component_metadata::ComponentMetadataResult::MergeFrom( + from._internal_component_metadata_result()); + } + if (cached_has_bits & 0x00000002u) { + _this->_internal_mutable_response()->::mavsdk::rpc::component_metadata::MetadataData::MergeFrom( + from._internal_response()); + } + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void GetMetadataResponse::CopyFrom(const GetMetadataResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata.GetMetadataResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool GetMetadataResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* GetMetadataResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void GetMetadataResponse::InternalSwap(GetMetadataResponse* 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(GetMetadataResponse, _impl_.response_) + + sizeof(GetMetadataResponse::_impl_.response_) + - PROTOBUF_FIELD_OFFSET(GetMetadataResponse, _impl_.component_metadata_result_)>( + reinterpret_cast(&_impl_.component_metadata_result_), + reinterpret_cast(&other->_impl_.component_metadata_result_)); +} + +::google::protobuf::Metadata GetMetadataResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[2]); +} +// =================================================================== + +class MetadataData::_Internal { + public: +}; + +MetadataData::MetadataData(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.MetadataData) +} +inline PROTOBUF_NDEBUG_INLINE MetadataData::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : json_metadata_(arena, from.json_metadata_), + _cached_size_{0} {} + +MetadataData::MetadataData( + ::google::protobuf::Arena* arena, + const MetadataData& from) + : ::google::protobuf::Message(arena) { + MetadataData* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.MetadataData) +} +inline PROTOBUF_NDEBUG_INLINE MetadataData::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : json_metadata_(arena), + _cached_size_{0} {} + +inline void MetadataData::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); +} +MetadataData::~MetadataData() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata.MetadataData) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void MetadataData::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.json_metadata_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void MetadataData::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata.MetadataData) + 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_.json_metadata_.ClearToEmpty(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* MetadataData::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 64, 2> MetadataData::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_MetadataData_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // string json_metadata = 1; + {::_pbi::TcParser::FastUS1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(MetadataData, _impl_.json_metadata_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // string json_metadata = 1; + {PROTOBUF_FIELD_OFFSET(MetadataData, _impl_.json_metadata_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\52\15\0\0\0\0\0\0" + "mavsdk.rpc.component_metadata.MetadataData" + "json_metadata" + }}, +}; + +::uint8_t* MetadataData::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata.MetadataData) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // string json_metadata = 1; + if (!this->_internal_json_metadata().empty()) { + const std::string& _s = this->_internal_json_metadata(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_metadata.MetadataData.json_metadata"); + target = stream->WriteStringMaybeAliased(1, _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.component_metadata.MetadataData) + return target; +} + +::size_t MetadataData::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata.MetadataData) + ::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 json_metadata = 1; + if (!this->_internal_json_metadata().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_json_metadata()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData MetadataData::_class_data_ = { + MetadataData::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* MetadataData::GetClassData() const { + return &_class_data_; +} + +void MetadataData::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.component_metadata.MetadataData) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_json_metadata().empty()) { + _this->_internal_set_json_metadata(from._internal_json_metadata()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void MetadataData::CopyFrom(const MetadataData& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata.MetadataData) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool MetadataData::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* MetadataData::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void MetadataData::InternalSwap(MetadataData* 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_.json_metadata_, &other->_impl_.json_metadata_, arena); +} + +::google::protobuf::Metadata MetadataData::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[3]); +} +// =================================================================== + +class ComponentMetadataResult::_Internal { + public: +}; + +ComponentMetadataResult::ComponentMetadataResult(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.ComponentMetadataResult) +} +inline PROTOBUF_NDEBUG_INLINE ComponentMetadataResult::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : result_str_(arena, from.result_str_), + _cached_size_{0} {} + +ComponentMetadataResult::ComponentMetadataResult( + ::google::protobuf::Arena* arena, + const ComponentMetadataResult& from) + : ::google::protobuf::Message(arena) { + ComponentMetadataResult* 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.component_metadata.ComponentMetadataResult) +} +inline PROTOBUF_NDEBUG_INLINE ComponentMetadataResult::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : result_str_(arena), + _cached_size_{0} {} + +inline void ComponentMetadataResult::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.result_ = {}; +} +ComponentMetadataResult::~ComponentMetadataResult() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata.ComponentMetadataResult) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ComponentMetadataResult::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.result_str_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ComponentMetadataResult::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata.ComponentMetadataResult) + 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* ComponentMetadataResult::_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, 72, 2> ComponentMetadataResult::_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 + &_ComponentMetadataResult_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // string result_str = 2; + {::_pbi::TcParser::FastUS1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(ComponentMetadataResult, _impl_.result_str_)}}, + // .mavsdk.rpc.component_metadata.ComponentMetadataResult.Result result = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ComponentMetadataResult, _impl_.result_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ComponentMetadataResult, _impl_.result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.component_metadata.ComponentMetadataResult.Result result = 1; + {PROTOBUF_FIELD_OFFSET(ComponentMetadataResult, _impl_.result_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + // string result_str = 2; + {PROTOBUF_FIELD_OFFSET(ComponentMetadataResult, _impl_.result_str_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\65\0\12\0\0\0\0\0" + "mavsdk.rpc.component_metadata.ComponentMetadataResult" + "result_str" + }}, +}; + +::uint8_t* ComponentMetadataResult::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata.ComponentMetadataResult) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // .mavsdk.rpc.component_metadata.ComponentMetadataResult.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.component_metadata.ComponentMetadataResult.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.component_metadata.ComponentMetadataResult) + return target; +} + +::size_t ComponentMetadataResult::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata.ComponentMetadataResult) + ::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.component_metadata.ComponentMetadataResult.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 ComponentMetadataResult::_class_data_ = { + ComponentMetadataResult::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ComponentMetadataResult::GetClassData() const { + return &_class_data_; +} + +void ComponentMetadataResult::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.component_metadata.ComponentMetadataResult) + 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 ComponentMetadataResult::CopyFrom(const ComponentMetadataResult& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata.ComponentMetadataResult) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ComponentMetadataResult::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ComponentMetadataResult::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ComponentMetadataResult::InternalSwap(ComponentMetadataResult* 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 ComponentMetadataResult::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[4]); +} +// =================================================================== + +class RequestComponentResponse::_Internal { + public: +}; + +RequestComponentResponse::RequestComponentResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.RequestComponentResponse) +} +RequestComponentResponse::RequestComponentResponse( + ::google::protobuf::Arena* arena, + const RequestComponentResponse& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + RequestComponentResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.RequestComponentResponse) +} + + + + + + + + + +::google::protobuf::Metadata RequestComponentResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[5]); +} +// =================================================================== + +class RequestAutopilotComponentRequest::_Internal { + public: +}; + +RequestAutopilotComponentRequest::RequestAutopilotComponentRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.RequestAutopilotComponentRequest) +} +RequestAutopilotComponentRequest::RequestAutopilotComponentRequest( + ::google::protobuf::Arena* arena, + const RequestAutopilotComponentRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + RequestAutopilotComponentRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.RequestAutopilotComponentRequest) +} + + + + + + + + + +::google::protobuf::Metadata RequestAutopilotComponentRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[6]); +} +// =================================================================== + +class RequestAutopilotComponentResponse::_Internal { + public: +}; + +RequestAutopilotComponentResponse::RequestAutopilotComponentResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.RequestAutopilotComponentResponse) +} +RequestAutopilotComponentResponse::RequestAutopilotComponentResponse( + ::google::protobuf::Arena* arena, + const RequestAutopilotComponentResponse& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + RequestAutopilotComponentResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.RequestAutopilotComponentResponse) +} + + + + + + + + + +::google::protobuf::Metadata RequestAutopilotComponentResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[7]); +} +// =================================================================== + +class SubscribeMetadataAvailableRequest::_Internal { + public: +}; + +SubscribeMetadataAvailableRequest::SubscribeMetadataAvailableRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.SubscribeMetadataAvailableRequest) +} +SubscribeMetadataAvailableRequest::SubscribeMetadataAvailableRequest( + ::google::protobuf::Arena* arena, + const SubscribeMetadataAvailableRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeMetadataAvailableRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.SubscribeMetadataAvailableRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeMetadataAvailableRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[8]); +} +// =================================================================== + +class MetadataAvailableResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(MetadataAvailableResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::component_metadata::MetadataUpdate& data(const MetadataAvailableResponse* msg); + static void set_has_data(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::component_metadata::MetadataUpdate& MetadataAvailableResponse::_Internal::data(const MetadataAvailableResponse* msg) { + return *msg->_impl_.data_; +} +MetadataAvailableResponse::MetadataAvailableResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.MetadataAvailableResponse) +} +inline PROTOBUF_NDEBUG_INLINE MetadataAvailableResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +MetadataAvailableResponse::MetadataAvailableResponse( + ::google::protobuf::Arena* arena, + const MetadataAvailableResponse& from) + : ::google::protobuf::Message(arena) { + MetadataAvailableResponse* 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_.data_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::component_metadata::MetadataUpdate>(arena, *from._impl_.data_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.MetadataAvailableResponse) +} +inline PROTOBUF_NDEBUG_INLINE MetadataAvailableResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void MetadataAvailableResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.data_ = {}; +} +MetadataAvailableResponse::~MetadataAvailableResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata.MetadataAvailableResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void MetadataAvailableResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.data_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void MetadataAvailableResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata.MetadataAvailableResponse) + 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_.data_ != nullptr); + _impl_.data_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* MetadataAvailableResponse::_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> MetadataAvailableResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(MetadataAvailableResponse, _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), + &_MetadataAvailableResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.component_metadata.MetadataUpdate data = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(MetadataAvailableResponse, _impl_.data_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.component_metadata.MetadataUpdate data = 1; + {PROTOBUF_FIELD_OFFSET(MetadataAvailableResponse, _impl_.data_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_metadata::MetadataUpdate>()}, + }}, {{ + }}, +}; + +::uint8_t* MetadataAvailableResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata.MetadataAvailableResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.component_metadata.MetadataUpdate data = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::data(this), + _Internal::data(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.component_metadata.MetadataAvailableResponse) + return target; +} + +::size_t MetadataAvailableResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata.MetadataAvailableResponse) + ::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.component_metadata.MetadataUpdate data = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.data_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData MetadataAvailableResponse::_class_data_ = { + MetadataAvailableResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* MetadataAvailableResponse::GetClassData() const { + return &_class_data_; +} + +void MetadataAvailableResponse::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.component_metadata.MetadataAvailableResponse) + 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_data()->::mavsdk::rpc::component_metadata::MetadataUpdate::MergeFrom( + from._internal_data()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void MetadataAvailableResponse::CopyFrom(const MetadataAvailableResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata.MetadataAvailableResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool MetadataAvailableResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* MetadataAvailableResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void MetadataAvailableResponse::InternalSwap(MetadataAvailableResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.data_, other->_impl_.data_); +} + +::google::protobuf::Metadata MetadataAvailableResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[9]); +} +// =================================================================== + +class MetadataUpdate::_Internal { + public: +}; + +MetadataUpdate::MetadataUpdate(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.MetadataUpdate) +} +inline PROTOBUF_NDEBUG_INLINE MetadataUpdate::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : json_metadata_(arena, from.json_metadata_), + _cached_size_{0} {} + +MetadataUpdate::MetadataUpdate( + ::google::protobuf::Arena* arena, + const MetadataUpdate& from) + : ::google::protobuf::Message(arena) { + MetadataUpdate* 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_, type_) - + offsetof(Impl_, compid_) + + sizeof(Impl_::type_)); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.MetadataUpdate) +} +inline PROTOBUF_NDEBUG_INLINE MetadataUpdate::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : json_metadata_(arena), + _cached_size_{0} {} + +inline void MetadataUpdate::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, compid_), + 0, + offsetof(Impl_, type_) - + offsetof(Impl_, compid_) + + sizeof(Impl_::type_)); +} +MetadataUpdate::~MetadataUpdate() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata.MetadataUpdate) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void MetadataUpdate::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.json_metadata_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void MetadataUpdate::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata.MetadataUpdate) + 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_.json_metadata_.ClearToEmpty(); + ::memset(&_impl_.compid_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.type_) - + reinterpret_cast(&_impl_.compid_)) + sizeof(_impl_.type_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* MetadataUpdate::_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, 0, 66, 2> MetadataUpdate::_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 + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_MetadataUpdate_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // uint32 compid = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(MetadataUpdate, _impl_.compid_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(MetadataUpdate, _impl_.compid_)}}, + // .mavsdk.rpc.component_metadata.MetadataType type = 2; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(MetadataUpdate, _impl_.type_), 63>(), + {16, 63, 0, PROTOBUF_FIELD_OFFSET(MetadataUpdate, _impl_.type_)}}, + // string json_metadata = 3; + {::_pbi::TcParser::FastUS1, + {26, 63, 0, PROTOBUF_FIELD_OFFSET(MetadataUpdate, _impl_.json_metadata_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // uint32 compid = 1; + {PROTOBUF_FIELD_OFFSET(MetadataUpdate, _impl_.compid_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // .mavsdk.rpc.component_metadata.MetadataType type = 2; + {PROTOBUF_FIELD_OFFSET(MetadataUpdate, _impl_.type_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + // string json_metadata = 3; + {PROTOBUF_FIELD_OFFSET(MetadataUpdate, _impl_.json_metadata_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\54\0\0\15\0\0\0\0" + "mavsdk.rpc.component_metadata.MetadataUpdate" + "json_metadata" + }}, +}; + +::uint8_t* MetadataUpdate::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata.MetadataUpdate) + ::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); + } + + // .mavsdk.rpc.component_metadata.MetadataType type = 2; + if (this->_internal_type() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 2, this->_internal_type(), target); + } + + // string json_metadata = 3; + if (!this->_internal_json_metadata().empty()) { + const std::string& _s = this->_internal_json_metadata(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_metadata.MetadataUpdate.json_metadata"); + target = stream->WriteStringMaybeAliased(3, _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.component_metadata.MetadataUpdate) + return target; +} + +::size_t MetadataUpdate::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata.MetadataUpdate) + ::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 json_metadata = 3; + if (!this->_internal_json_metadata().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_json_metadata()); + } + + // uint32 compid = 1; + if (this->_internal_compid() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_compid()); + } + + // .mavsdk.rpc.component_metadata.MetadataType type = 2; + if (this->_internal_type() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_type()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData MetadataUpdate::_class_data_ = { + MetadataUpdate::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* MetadataUpdate::GetClassData() const { + return &_class_data_; +} + +void MetadataUpdate::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.component_metadata.MetadataUpdate) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_json_metadata().empty()) { + _this->_internal_set_json_metadata(from._internal_json_metadata()); + } + if (from._internal_compid() != 0) { + _this->_internal_set_compid(from._internal_compid()); + } + if (from._internal_type() != 0) { + _this->_internal_set_type(from._internal_type()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void MetadataUpdate::CopyFrom(const MetadataUpdate& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata.MetadataUpdate) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool MetadataUpdate::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* MetadataUpdate::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void MetadataUpdate::InternalSwap(MetadataUpdate* 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_.json_metadata_, &other->_impl_.json_metadata_, arena); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(MetadataUpdate, _impl_.type_) + + sizeof(MetadataUpdate::_impl_.type_) + - PROTOBUF_FIELD_OFFSET(MetadataUpdate, _impl_.compid_)>( + reinterpret_cast(&_impl_.compid_), + reinterpret_cast(&other->_impl_.compid_)); +} + +::google::protobuf::Metadata MetadataUpdate::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_getter, &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto_once, + file_level_metadata_component_5fmetadata_2fcomponent_5fmetadata_2eproto[10]); +} +// @@protoc_insertion_point(namespace_scope) +} // namespace component_metadata +} // 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/component_metadata/component_metadata.pb.h b/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.h new file mode 100644 index 0000000000..d0ac7ea83c --- /dev/null +++ b/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.h @@ -0,0 +1,2754 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: component_metadata/component_metadata.proto +// Protobuf C++ Version: 4.25.1 + +#ifndef GOOGLE_PROTOBUF_INCLUDED_component_5fmetadata_2fcomponent_5fmetadata_2eproto_2epb_2eh +#define GOOGLE_PROTOBUF_INCLUDED_component_5fmetadata_2fcomponent_5fmetadata_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_component_5fmetadata_2fcomponent_5fmetadata_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_component_5fmetadata_2fcomponent_5fmetadata_2eproto { + static const ::uint32_t offsets[]; +}; +extern const ::google::protobuf::internal::DescriptorTable + descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +namespace mavsdk { +namespace rpc { +namespace component_metadata { +class ComponentMetadataResult; +struct ComponentMetadataResultDefaultTypeInternal; +extern ComponentMetadataResultDefaultTypeInternal _ComponentMetadataResult_default_instance_; +class GetMetadataRequest; +struct GetMetadataRequestDefaultTypeInternal; +extern GetMetadataRequestDefaultTypeInternal _GetMetadataRequest_default_instance_; +class GetMetadataResponse; +struct GetMetadataResponseDefaultTypeInternal; +extern GetMetadataResponseDefaultTypeInternal _GetMetadataResponse_default_instance_; +class MetadataAvailableResponse; +struct MetadataAvailableResponseDefaultTypeInternal; +extern MetadataAvailableResponseDefaultTypeInternal _MetadataAvailableResponse_default_instance_; +class MetadataData; +struct MetadataDataDefaultTypeInternal; +extern MetadataDataDefaultTypeInternal _MetadataData_default_instance_; +class MetadataUpdate; +struct MetadataUpdateDefaultTypeInternal; +extern MetadataUpdateDefaultTypeInternal _MetadataUpdate_default_instance_; +class RequestAutopilotComponentRequest; +struct RequestAutopilotComponentRequestDefaultTypeInternal; +extern RequestAutopilotComponentRequestDefaultTypeInternal _RequestAutopilotComponentRequest_default_instance_; +class RequestAutopilotComponentResponse; +struct RequestAutopilotComponentResponseDefaultTypeInternal; +extern RequestAutopilotComponentResponseDefaultTypeInternal _RequestAutopilotComponentResponse_default_instance_; +class RequestComponentRequest; +struct RequestComponentRequestDefaultTypeInternal; +extern RequestComponentRequestDefaultTypeInternal _RequestComponentRequest_default_instance_; +class RequestComponentResponse; +struct RequestComponentResponseDefaultTypeInternal; +extern RequestComponentResponseDefaultTypeInternal _RequestComponentResponse_default_instance_; +class SubscribeMetadataAvailableRequest; +struct SubscribeMetadataAvailableRequestDefaultTypeInternal; +extern SubscribeMetadataAvailableRequestDefaultTypeInternal _SubscribeMetadataAvailableRequest_default_instance_; +} // namespace component_metadata +} // namespace rpc +} // namespace mavsdk +namespace google { +namespace protobuf { +} // namespace protobuf +} // namespace google + +namespace mavsdk { +namespace rpc { +namespace component_metadata { +enum ComponentMetadataResult_Result : int { + ComponentMetadataResult_Result_RESULT_SUCCESS = 0, + ComponentMetadataResult_Result_RESULT_NOT_AVAILABLE = 1, + ComponentMetadataResult_Result_RESULT_CONNECTION_ERROR = 2, + ComponentMetadataResult_Result_RESULT_UNSUPPORTED = 3, + ComponentMetadataResult_Result_RESULT_DENIED = 4, + ComponentMetadataResult_Result_RESULT_FAILED = 5, + ComponentMetadataResult_Result_RESULT_TIMEOUT = 6, + ComponentMetadataResult_Result_RESULT_NO_SYSTEM = 7, + ComponentMetadataResult_Result_RESULT_NOT_REQUESTED = 8, + ComponentMetadataResult_Result_ComponentMetadataResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + ComponentMetadataResult_Result_ComponentMetadataResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool ComponentMetadataResult_Result_IsValid(int value); +extern const uint32_t ComponentMetadataResult_Result_internal_data_[]; +constexpr ComponentMetadataResult_Result ComponentMetadataResult_Result_Result_MIN = static_cast(0); +constexpr ComponentMetadataResult_Result ComponentMetadataResult_Result_Result_MAX = static_cast(8); +constexpr int ComponentMetadataResult_Result_Result_ARRAYSIZE = 8 + 1; +const ::google::protobuf::EnumDescriptor* +ComponentMetadataResult_Result_descriptor(); +template +const std::string& ComponentMetadataResult_Result_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to Result_Name()."); + return ComponentMetadataResult_Result_Name(static_cast(value)); +} +template <> +inline const std::string& ComponentMetadataResult_Result_Name(ComponentMetadataResult_Result value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool ComponentMetadataResult_Result_Parse(absl::string_view name, ComponentMetadataResult_Result* value) { + return ::google::protobuf::internal::ParseNamedEnum( + ComponentMetadataResult_Result_descriptor(), name, value); +} +enum MetadataType : int { + METADATA_TYPE_ALL_COMPLETED = 0, + METADATA_TYPE_PARAMETER = 1, + METADATA_TYPE_EVENTS = 2, + METADATA_TYPE_ACTUATORS = 3, + MetadataType_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + MetadataType_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool MetadataType_IsValid(int value); +extern const uint32_t MetadataType_internal_data_[]; +constexpr MetadataType MetadataType_MIN = static_cast(0); +constexpr MetadataType MetadataType_MAX = static_cast(3); +constexpr int MetadataType_ARRAYSIZE = 3 + 1; +const ::google::protobuf::EnumDescriptor* +MetadataType_descriptor(); +template +const std::string& MetadataType_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to MetadataType_Name()."); + return MetadataType_Name(static_cast(value)); +} +template <> +inline const std::string& MetadataType_Name(MetadataType value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool MetadataType_Parse(absl::string_view name, MetadataType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + MetadataType_descriptor(), name, value); +} + +// =================================================================== + + +// ------------------------------------------------------------------- + +class SubscribeMetadataAvailableRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.SubscribeMetadataAvailableRequest) */ { + public: + inline SubscribeMetadataAvailableRequest() : SubscribeMetadataAvailableRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeMetadataAvailableRequest(::google::protobuf::internal::ConstantInitialized); + + inline SubscribeMetadataAvailableRequest(const SubscribeMetadataAvailableRequest& from) + : SubscribeMetadataAvailableRequest(nullptr, from) {} + SubscribeMetadataAvailableRequest(SubscribeMetadataAvailableRequest&& from) noexcept + : SubscribeMetadataAvailableRequest() { + *this = ::std::move(from); + } + + inline SubscribeMetadataAvailableRequest& operator=(const SubscribeMetadataAvailableRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeMetadataAvailableRequest& operator=(SubscribeMetadataAvailableRequest&& 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 SubscribeMetadataAvailableRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeMetadataAvailableRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeMetadataAvailableRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 8; + + friend void swap(SubscribeMetadataAvailableRequest& a, SubscribeMetadataAvailableRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeMetadataAvailableRequest* 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(SubscribeMetadataAvailableRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeMetadataAvailableRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeMetadataAvailableRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeMetadataAvailableRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.SubscribeMetadataAvailableRequest"; + } + protected: + explicit SubscribeMetadataAvailableRequest(::google::protobuf::Arena* arena); + SubscribeMetadataAvailableRequest(::google::protobuf::Arena* arena, const SubscribeMetadataAvailableRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.SubscribeMetadataAvailableRequest) + 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_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class RequestComponentResponse final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.RequestComponentResponse) */ { + public: + inline RequestComponentResponse() : RequestComponentResponse(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR RequestComponentResponse(::google::protobuf::internal::ConstantInitialized); + + inline RequestComponentResponse(const RequestComponentResponse& from) + : RequestComponentResponse(nullptr, from) {} + RequestComponentResponse(RequestComponentResponse&& from) noexcept + : RequestComponentResponse() { + *this = ::std::move(from); + } + + inline RequestComponentResponse& operator=(const RequestComponentResponse& from) { + CopyFrom(from); + return *this; + } + inline RequestComponentResponse& operator=(RequestComponentResponse&& 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 RequestComponentResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RequestComponentResponse* internal_default_instance() { + return reinterpret_cast( + &_RequestComponentResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + friend void swap(RequestComponentResponse& a, RequestComponentResponse& b) { + a.Swap(&b); + } + inline void Swap(RequestComponentResponse* 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(RequestComponentResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RequestComponentResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const RequestComponentResponse& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const RequestComponentResponse& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.RequestComponentResponse"; + } + protected: + explicit RequestComponentResponse(::google::protobuf::Arena* arena); + RequestComponentResponse(::google::protobuf::Arena* arena, const RequestComponentResponse& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.RequestComponentResponse) + 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_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class RequestComponentRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.RequestComponentRequest) */ { + public: + inline RequestComponentRequest() : RequestComponentRequest(nullptr) {} + ~RequestComponentRequest() override; + template + explicit PROTOBUF_CONSTEXPR RequestComponentRequest(::google::protobuf::internal::ConstantInitialized); + + inline RequestComponentRequest(const RequestComponentRequest& from) + : RequestComponentRequest(nullptr, from) {} + RequestComponentRequest(RequestComponentRequest&& from) noexcept + : RequestComponentRequest() { + *this = ::std::move(from); + } + + inline RequestComponentRequest& operator=(const RequestComponentRequest& from) { + CopyFrom(from); + return *this; + } + inline RequestComponentRequest& operator=(RequestComponentRequest&& 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 RequestComponentRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RequestComponentRequest* internal_default_instance() { + return reinterpret_cast( + &_RequestComponentRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + friend void swap(RequestComponentRequest& a, RequestComponentRequest& b) { + a.Swap(&b); + } + inline void Swap(RequestComponentRequest* 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(RequestComponentRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RequestComponentRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const RequestComponentRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const RequestComponentRequest& from) { + RequestComponentRequest::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(RequestComponentRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.RequestComponentRequest"; + } + protected: + explicit RequestComponentRequest(::google::protobuf::Arena* arena); + RequestComponentRequest(::google::protobuf::Arena* arena, const RequestComponentRequest& 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 { + kCompidFieldNumber = 1, + }; + // 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: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.RequestComponentRequest) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + 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); + ::uint32_t compid_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class RequestAutopilotComponentResponse final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.RequestAutopilotComponentResponse) */ { + public: + inline RequestAutopilotComponentResponse() : RequestAutopilotComponentResponse(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR RequestAutopilotComponentResponse(::google::protobuf::internal::ConstantInitialized); + + inline RequestAutopilotComponentResponse(const RequestAutopilotComponentResponse& from) + : RequestAutopilotComponentResponse(nullptr, from) {} + RequestAutopilotComponentResponse(RequestAutopilotComponentResponse&& from) noexcept + : RequestAutopilotComponentResponse() { + *this = ::std::move(from); + } + + inline RequestAutopilotComponentResponse& operator=(const RequestAutopilotComponentResponse& from) { + CopyFrom(from); + return *this; + } + inline RequestAutopilotComponentResponse& operator=(RequestAutopilotComponentResponse&& 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 RequestAutopilotComponentResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RequestAutopilotComponentResponse* internal_default_instance() { + return reinterpret_cast( + &_RequestAutopilotComponentResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 7; + + friend void swap(RequestAutopilotComponentResponse& a, RequestAutopilotComponentResponse& b) { + a.Swap(&b); + } + inline void Swap(RequestAutopilotComponentResponse* 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(RequestAutopilotComponentResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RequestAutopilotComponentResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const RequestAutopilotComponentResponse& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const RequestAutopilotComponentResponse& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.RequestAutopilotComponentResponse"; + } + protected: + explicit RequestAutopilotComponentResponse(::google::protobuf::Arena* arena); + RequestAutopilotComponentResponse(::google::protobuf::Arena* arena, const RequestAutopilotComponentResponse& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.RequestAutopilotComponentResponse) + 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_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class RequestAutopilotComponentRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.RequestAutopilotComponentRequest) */ { + public: + inline RequestAutopilotComponentRequest() : RequestAutopilotComponentRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR RequestAutopilotComponentRequest(::google::protobuf::internal::ConstantInitialized); + + inline RequestAutopilotComponentRequest(const RequestAutopilotComponentRequest& from) + : RequestAutopilotComponentRequest(nullptr, from) {} + RequestAutopilotComponentRequest(RequestAutopilotComponentRequest&& from) noexcept + : RequestAutopilotComponentRequest() { + *this = ::std::move(from); + } + + inline RequestAutopilotComponentRequest& operator=(const RequestAutopilotComponentRequest& from) { + CopyFrom(from); + return *this; + } + inline RequestAutopilotComponentRequest& operator=(RequestAutopilotComponentRequest&& 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 RequestAutopilotComponentRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RequestAutopilotComponentRequest* internal_default_instance() { + return reinterpret_cast( + &_RequestAutopilotComponentRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + friend void swap(RequestAutopilotComponentRequest& a, RequestAutopilotComponentRequest& b) { + a.Swap(&b); + } + inline void Swap(RequestAutopilotComponentRequest* 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(RequestAutopilotComponentRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RequestAutopilotComponentRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const RequestAutopilotComponentRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const RequestAutopilotComponentRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.RequestAutopilotComponentRequest"; + } + protected: + explicit RequestAutopilotComponentRequest(::google::protobuf::Arena* arena); + RequestAutopilotComponentRequest(::google::protobuf::Arena* arena, const RequestAutopilotComponentRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.RequestAutopilotComponentRequest) + 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_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class MetadataUpdate final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.MetadataUpdate) */ { + public: + inline MetadataUpdate() : MetadataUpdate(nullptr) {} + ~MetadataUpdate() override; + template + explicit PROTOBUF_CONSTEXPR MetadataUpdate(::google::protobuf::internal::ConstantInitialized); + + inline MetadataUpdate(const MetadataUpdate& from) + : MetadataUpdate(nullptr, from) {} + MetadataUpdate(MetadataUpdate&& from) noexcept + : MetadataUpdate() { + *this = ::std::move(from); + } + + inline MetadataUpdate& operator=(const MetadataUpdate& from) { + CopyFrom(from); + return *this; + } + inline MetadataUpdate& operator=(MetadataUpdate&& 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 MetadataUpdate& default_instance() { + return *internal_default_instance(); + } + static inline const MetadataUpdate* internal_default_instance() { + return reinterpret_cast( + &_MetadataUpdate_default_instance_); + } + static constexpr int kIndexInFileMessages = + 10; + + friend void swap(MetadataUpdate& a, MetadataUpdate& b) { + a.Swap(&b); + } + inline void Swap(MetadataUpdate* 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(MetadataUpdate* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + MetadataUpdate* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const MetadataUpdate& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const MetadataUpdate& from) { + MetadataUpdate::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(MetadataUpdate* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.MetadataUpdate"; + } + protected: + explicit MetadataUpdate(::google::protobuf::Arena* arena); + MetadataUpdate(::google::protobuf::Arena* arena, const MetadataUpdate& 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 { + kJsonMetadataFieldNumber = 3, + kCompidFieldNumber = 1, + kTypeFieldNumber = 2, + }; + // string json_metadata = 3; + void clear_json_metadata() ; + const std::string& json_metadata() const; + template + void set_json_metadata(Arg_&& arg, Args_... args); + std::string* mutable_json_metadata(); + PROTOBUF_NODISCARD std::string* release_json_metadata(); + void set_allocated_json_metadata(std::string* value); + + private: + const std::string& _internal_json_metadata() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_json_metadata( + const std::string& value); + std::string* _internal_mutable_json_metadata(); + + 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.component_metadata.MetadataType type = 2; + void clear_type() ; + ::mavsdk::rpc::component_metadata::MetadataType type() const; + void set_type(::mavsdk::rpc::component_metadata::MetadataType value); + + private: + ::mavsdk::rpc::component_metadata::MetadataType _internal_type() const; + void _internal_set_type(::mavsdk::rpc::component_metadata::MetadataType value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.MetadataUpdate) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 2, 3, 0, + 66, 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 json_metadata_; + ::uint32_t compid_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class MetadataData final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.MetadataData) */ { + public: + inline MetadataData() : MetadataData(nullptr) {} + ~MetadataData() override; + template + explicit PROTOBUF_CONSTEXPR MetadataData(::google::protobuf::internal::ConstantInitialized); + + inline MetadataData(const MetadataData& from) + : MetadataData(nullptr, from) {} + MetadataData(MetadataData&& from) noexcept + : MetadataData() { + *this = ::std::move(from); + } + + inline MetadataData& operator=(const MetadataData& from) { + CopyFrom(from); + return *this; + } + inline MetadataData& operator=(MetadataData&& 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 MetadataData& default_instance() { + return *internal_default_instance(); + } + static inline const MetadataData* internal_default_instance() { + return reinterpret_cast( + &_MetadataData_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + friend void swap(MetadataData& a, MetadataData& b) { + a.Swap(&b); + } + inline void Swap(MetadataData* 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(MetadataData* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + MetadataData* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const MetadataData& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const MetadataData& from) { + MetadataData::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(MetadataData* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.MetadataData"; + } + protected: + explicit MetadataData(::google::protobuf::Arena* arena); + MetadataData(::google::protobuf::Arena* arena, const MetadataData& 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 { + kJsonMetadataFieldNumber = 1, + }; + // string json_metadata = 1; + void clear_json_metadata() ; + const std::string& json_metadata() const; + template + void set_json_metadata(Arg_&& arg, Args_... args); + std::string* mutable_json_metadata(); + PROTOBUF_NODISCARD std::string* release_json_metadata(); + void set_allocated_json_metadata(std::string* value); + + private: + const std::string& _internal_json_metadata() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_json_metadata( + const std::string& value); + std::string* _internal_mutable_json_metadata(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.MetadataData) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 64, 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 json_metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class GetMetadataRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.GetMetadataRequest) */ { + public: + inline GetMetadataRequest() : GetMetadataRequest(nullptr) {} + ~GetMetadataRequest() override; + template + explicit PROTOBUF_CONSTEXPR GetMetadataRequest(::google::protobuf::internal::ConstantInitialized); + + inline GetMetadataRequest(const GetMetadataRequest& from) + : GetMetadataRequest(nullptr, from) {} + GetMetadataRequest(GetMetadataRequest&& from) noexcept + : GetMetadataRequest() { + *this = ::std::move(from); + } + + inline GetMetadataRequest& operator=(const GetMetadataRequest& from) { + CopyFrom(from); + return *this; + } + inline GetMetadataRequest& operator=(GetMetadataRequest&& 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 GetMetadataRequest& default_instance() { + return *internal_default_instance(); + } + static inline const GetMetadataRequest* internal_default_instance() { + return reinterpret_cast( + &_GetMetadataRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + friend void swap(GetMetadataRequest& a, GetMetadataRequest& b) { + a.Swap(&b); + } + inline void Swap(GetMetadataRequest* 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(GetMetadataRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GetMetadataRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const GetMetadataRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const GetMetadataRequest& from) { + GetMetadataRequest::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(GetMetadataRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.GetMetadataRequest"; + } + protected: + explicit GetMetadataRequest(::google::protobuf::Arena* arena); + GetMetadataRequest(::google::protobuf::Arena* arena, const GetMetadataRequest& 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 { + kCompidFieldNumber = 1, + kMetadataTypeFieldNumber = 2, + }; + // 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.component_metadata.MetadataType metadata_type = 2; + void clear_metadata_type() ; + ::mavsdk::rpc::component_metadata::MetadataType metadata_type() const; + void set_metadata_type(::mavsdk::rpc::component_metadata::MetadataType value); + + private: + ::mavsdk::rpc::component_metadata::MetadataType _internal_metadata_type() const; + void _internal_set_metadata_type(::mavsdk::rpc::component_metadata::MetadataType value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.GetMetadataRequest) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 0, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + 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); + ::uint32_t compid_; + int metadata_type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class ComponentMetadataResult final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.ComponentMetadataResult) */ { + public: + inline ComponentMetadataResult() : ComponentMetadataResult(nullptr) {} + ~ComponentMetadataResult() override; + template + explicit PROTOBUF_CONSTEXPR ComponentMetadataResult(::google::protobuf::internal::ConstantInitialized); + + inline ComponentMetadataResult(const ComponentMetadataResult& from) + : ComponentMetadataResult(nullptr, from) {} + ComponentMetadataResult(ComponentMetadataResult&& from) noexcept + : ComponentMetadataResult() { + *this = ::std::move(from); + } + + inline ComponentMetadataResult& operator=(const ComponentMetadataResult& from) { + CopyFrom(from); + return *this; + } + inline ComponentMetadataResult& operator=(ComponentMetadataResult&& 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 ComponentMetadataResult& default_instance() { + return *internal_default_instance(); + } + static inline const ComponentMetadataResult* internal_default_instance() { + return reinterpret_cast( + &_ComponentMetadataResult_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + friend void swap(ComponentMetadataResult& a, ComponentMetadataResult& b) { + a.Swap(&b); + } + inline void Swap(ComponentMetadataResult* 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(ComponentMetadataResult* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ComponentMetadataResult* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ComponentMetadataResult& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ComponentMetadataResult& from) { + ComponentMetadataResult::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(ComponentMetadataResult* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.ComponentMetadataResult"; + } + protected: + explicit ComponentMetadataResult(::google::protobuf::Arena* arena); + ComponentMetadataResult(::google::protobuf::Arena* arena, const ComponentMetadataResult& 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 = ComponentMetadataResult_Result; + static constexpr Result RESULT_SUCCESS = ComponentMetadataResult_Result_RESULT_SUCCESS; + static constexpr Result RESULT_NOT_AVAILABLE = ComponentMetadataResult_Result_RESULT_NOT_AVAILABLE; + static constexpr Result RESULT_CONNECTION_ERROR = ComponentMetadataResult_Result_RESULT_CONNECTION_ERROR; + static constexpr Result RESULT_UNSUPPORTED = ComponentMetadataResult_Result_RESULT_UNSUPPORTED; + static constexpr Result RESULT_DENIED = ComponentMetadataResult_Result_RESULT_DENIED; + static constexpr Result RESULT_FAILED = ComponentMetadataResult_Result_RESULT_FAILED; + static constexpr Result RESULT_TIMEOUT = ComponentMetadataResult_Result_RESULT_TIMEOUT; + static constexpr Result RESULT_NO_SYSTEM = ComponentMetadataResult_Result_RESULT_NO_SYSTEM; + static constexpr Result RESULT_NOT_REQUESTED = ComponentMetadataResult_Result_RESULT_NOT_REQUESTED; + static inline bool Result_IsValid(int value) { + return ComponentMetadataResult_Result_IsValid(value); + } + static constexpr Result Result_MIN = ComponentMetadataResult_Result_Result_MIN; + static constexpr Result Result_MAX = ComponentMetadataResult_Result_Result_MAX; + static constexpr int Result_ARRAYSIZE = ComponentMetadataResult_Result_Result_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* Result_descriptor() { + return ComponentMetadataResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T value) { + return ComponentMetadataResult_Result_Name(value); + } + static inline bool Result_Parse(absl::string_view name, Result* value) { + return ComponentMetadataResult_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.component_metadata.ComponentMetadataResult.Result result = 1; + void clear_result() ; + ::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result result() const; + void set_result(::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result value); + + private: + ::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result _internal_result() const; + void _internal_set_result(::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.ComponentMetadataResult) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 0, + 72, 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_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class MetadataAvailableResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.MetadataAvailableResponse) */ { + public: + inline MetadataAvailableResponse() : MetadataAvailableResponse(nullptr) {} + ~MetadataAvailableResponse() override; + template + explicit PROTOBUF_CONSTEXPR MetadataAvailableResponse(::google::protobuf::internal::ConstantInitialized); + + inline MetadataAvailableResponse(const MetadataAvailableResponse& from) + : MetadataAvailableResponse(nullptr, from) {} + MetadataAvailableResponse(MetadataAvailableResponse&& from) noexcept + : MetadataAvailableResponse() { + *this = ::std::move(from); + } + + inline MetadataAvailableResponse& operator=(const MetadataAvailableResponse& from) { + CopyFrom(from); + return *this; + } + inline MetadataAvailableResponse& operator=(MetadataAvailableResponse&& 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 MetadataAvailableResponse& default_instance() { + return *internal_default_instance(); + } + static inline const MetadataAvailableResponse* internal_default_instance() { + return reinterpret_cast( + &_MetadataAvailableResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 9; + + friend void swap(MetadataAvailableResponse& a, MetadataAvailableResponse& b) { + a.Swap(&b); + } + inline void Swap(MetadataAvailableResponse* 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(MetadataAvailableResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + MetadataAvailableResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const MetadataAvailableResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const MetadataAvailableResponse& from) { + MetadataAvailableResponse::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(MetadataAvailableResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.MetadataAvailableResponse"; + } + protected: + explicit MetadataAvailableResponse(::google::protobuf::Arena* arena); + MetadataAvailableResponse(::google::protobuf::Arena* arena, const MetadataAvailableResponse& 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 { + kDataFieldNumber = 1, + }; + // .mavsdk.rpc.component_metadata.MetadataUpdate data = 1; + bool has_data() const; + void clear_data() ; + const ::mavsdk::rpc::component_metadata::MetadataUpdate& data() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::component_metadata::MetadataUpdate* release_data(); + ::mavsdk::rpc::component_metadata::MetadataUpdate* mutable_data(); + void set_allocated_data(::mavsdk::rpc::component_metadata::MetadataUpdate* value); + void unsafe_arena_set_allocated_data(::mavsdk::rpc::component_metadata::MetadataUpdate* value); + ::mavsdk::rpc::component_metadata::MetadataUpdate* unsafe_arena_release_data(); + + private: + const ::mavsdk::rpc::component_metadata::MetadataUpdate& _internal_data() const; + ::mavsdk::rpc::component_metadata::MetadataUpdate* _internal_mutable_data(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.MetadataAvailableResponse) + 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::component_metadata::MetadataUpdate* data_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +};// ------------------------------------------------------------------- + +class GetMetadataResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata.GetMetadataResponse) */ { + public: + inline GetMetadataResponse() : GetMetadataResponse(nullptr) {} + ~GetMetadataResponse() override; + template + explicit PROTOBUF_CONSTEXPR GetMetadataResponse(::google::protobuf::internal::ConstantInitialized); + + inline GetMetadataResponse(const GetMetadataResponse& from) + : GetMetadataResponse(nullptr, from) {} + GetMetadataResponse(GetMetadataResponse&& from) noexcept + : GetMetadataResponse() { + *this = ::std::move(from); + } + + inline GetMetadataResponse& operator=(const GetMetadataResponse& from) { + CopyFrom(from); + return *this; + } + inline GetMetadataResponse& operator=(GetMetadataResponse&& 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 GetMetadataResponse& default_instance() { + return *internal_default_instance(); + } + static inline const GetMetadataResponse* internal_default_instance() { + return reinterpret_cast( + &_GetMetadataResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(GetMetadataResponse& a, GetMetadataResponse& b) { + a.Swap(&b); + } + inline void Swap(GetMetadataResponse* 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(GetMetadataResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GetMetadataResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const GetMetadataResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const GetMetadataResponse& from) { + GetMetadataResponse::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(GetMetadataResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata.GetMetadataResponse"; + } + protected: + explicit GetMetadataResponse(::google::protobuf::Arena* arena); + GetMetadataResponse(::google::protobuf::Arena* arena, const GetMetadataResponse& 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 { + kComponentMetadataResultFieldNumber = 1, + kResponseFieldNumber = 2, + }; + // .mavsdk.rpc.component_metadata.ComponentMetadataResult component_metadata_result = 1; + bool has_component_metadata_result() const; + void clear_component_metadata_result() ; + const ::mavsdk::rpc::component_metadata::ComponentMetadataResult& component_metadata_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::component_metadata::ComponentMetadataResult* release_component_metadata_result(); + ::mavsdk::rpc::component_metadata::ComponentMetadataResult* mutable_component_metadata_result(); + void set_allocated_component_metadata_result(::mavsdk::rpc::component_metadata::ComponentMetadataResult* value); + void unsafe_arena_set_allocated_component_metadata_result(::mavsdk::rpc::component_metadata::ComponentMetadataResult* value); + ::mavsdk::rpc::component_metadata::ComponentMetadataResult* unsafe_arena_release_component_metadata_result(); + + private: + const ::mavsdk::rpc::component_metadata::ComponentMetadataResult& _internal_component_metadata_result() const; + ::mavsdk::rpc::component_metadata::ComponentMetadataResult* _internal_mutable_component_metadata_result(); + + public: + // .mavsdk.rpc.component_metadata.MetadataData response = 2; + bool has_response() const; + void clear_response() ; + const ::mavsdk::rpc::component_metadata::MetadataData& response() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::component_metadata::MetadataData* release_response(); + ::mavsdk::rpc::component_metadata::MetadataData* mutable_response(); + void set_allocated_response(::mavsdk::rpc::component_metadata::MetadataData* value); + void unsafe_arena_set_allocated_response(::mavsdk::rpc::component_metadata::MetadataData* value); + ::mavsdk::rpc::component_metadata::MetadataData* unsafe_arena_release_response(); + + private: + const ::mavsdk::rpc::component_metadata::MetadataData& _internal_response() const; + ::mavsdk::rpc::component_metadata::MetadataData* _internal_mutable_response(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata.GetMetadataResponse) + 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::component_metadata::ComponentMetadataResult* component_metadata_result_; + ::mavsdk::rpc::component_metadata::MetadataData* response_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_component_5fmetadata_2fcomponent_5fmetadata_2eproto; +}; + +// =================================================================== + + + + +// =================================================================== + + +#ifdef __GNUC__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// RequestComponentRequest + +// uint32 compid = 1; +inline void RequestComponentRequest::clear_compid() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.compid_ = 0u; +} +inline ::uint32_t RequestComponentRequest::compid() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.RequestComponentRequest.compid) + return _internal_compid(); +} +inline void RequestComponentRequest::set_compid(::uint32_t value) { + _internal_set_compid(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata.RequestComponentRequest.compid) +} +inline ::uint32_t RequestComponentRequest::_internal_compid() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.compid_; +} +inline void RequestComponentRequest::_internal_set_compid(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.compid_ = value; +} + +// ------------------------------------------------------------------- + +// GetMetadataRequest + +// uint32 compid = 1; +inline void GetMetadataRequest::clear_compid() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.compid_ = 0u; +} +inline ::uint32_t GetMetadataRequest::compid() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.GetMetadataRequest.compid) + return _internal_compid(); +} +inline void GetMetadataRequest::set_compid(::uint32_t value) { + _internal_set_compid(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata.GetMetadataRequest.compid) +} +inline ::uint32_t GetMetadataRequest::_internal_compid() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.compid_; +} +inline void GetMetadataRequest::_internal_set_compid(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.compid_ = value; +} + +// .mavsdk.rpc.component_metadata.MetadataType metadata_type = 2; +inline void GetMetadataRequest::clear_metadata_type() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.metadata_type_ = 0; +} +inline ::mavsdk::rpc::component_metadata::MetadataType GetMetadataRequest::metadata_type() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.GetMetadataRequest.metadata_type) + return _internal_metadata_type(); +} +inline void GetMetadataRequest::set_metadata_type(::mavsdk::rpc::component_metadata::MetadataType value) { + _internal_set_metadata_type(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata.GetMetadataRequest.metadata_type) +} +inline ::mavsdk::rpc::component_metadata::MetadataType GetMetadataRequest::_internal_metadata_type() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::component_metadata::MetadataType>(_impl_.metadata_type_); +} +inline void GetMetadataRequest::_internal_set_metadata_type(::mavsdk::rpc::component_metadata::MetadataType value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.metadata_type_ = value; +} + +// ------------------------------------------------------------------- + +// GetMetadataResponse + +// .mavsdk.rpc.component_metadata.ComponentMetadataResult component_metadata_result = 1; +inline bool GetMetadataResponse::has_component_metadata_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.component_metadata_result_ != nullptr); + return value; +} +inline void GetMetadataResponse::clear_component_metadata_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.component_metadata_result_ != nullptr) _impl_.component_metadata_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::component_metadata::ComponentMetadataResult& GetMetadataResponse::_internal_component_metadata_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::component_metadata::ComponentMetadataResult* p = _impl_.component_metadata_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::component_metadata::_ComponentMetadataResult_default_instance_); +} +inline const ::mavsdk::rpc::component_metadata::ComponentMetadataResult& GetMetadataResponse::component_metadata_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.GetMetadataResponse.component_metadata_result) + return _internal_component_metadata_result(); +} +inline void GetMetadataResponse::unsafe_arena_set_allocated_component_metadata_result(::mavsdk::rpc::component_metadata::ComponentMetadataResult* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.component_metadata_result_); + } + _impl_.component_metadata_result_ = reinterpret_cast<::mavsdk::rpc::component_metadata::ComponentMetadataResult*>(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.component_metadata.GetMetadataResponse.component_metadata_result) +} +inline ::mavsdk::rpc::component_metadata::ComponentMetadataResult* GetMetadataResponse::release_component_metadata_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::component_metadata::ComponentMetadataResult* released = _impl_.component_metadata_result_; + _impl_.component_metadata_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::component_metadata::ComponentMetadataResult* GetMetadataResponse::unsafe_arena_release_component_metadata_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_metadata.GetMetadataResponse.component_metadata_result) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::component_metadata::ComponentMetadataResult* temp = _impl_.component_metadata_result_; + _impl_.component_metadata_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::component_metadata::ComponentMetadataResult* GetMetadataResponse::_internal_mutable_component_metadata_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.component_metadata_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::component_metadata::ComponentMetadataResult>(GetArena()); + _impl_.component_metadata_result_ = reinterpret_cast<::mavsdk::rpc::component_metadata::ComponentMetadataResult*>(p); + } + return _impl_.component_metadata_result_; +} +inline ::mavsdk::rpc::component_metadata::ComponentMetadataResult* GetMetadataResponse::mutable_component_metadata_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::component_metadata::ComponentMetadataResult* _msg = _internal_mutable_component_metadata_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_metadata.GetMetadataResponse.component_metadata_result) + return _msg; +} +inline void GetMetadataResponse::set_allocated_component_metadata_result(::mavsdk::rpc::component_metadata::ComponentMetadataResult* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::component_metadata::ComponentMetadataResult*>(_impl_.component_metadata_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::component_metadata::ComponentMetadataResult*>(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_.component_metadata_result_ = reinterpret_cast<::mavsdk::rpc::component_metadata::ComponentMetadataResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_metadata.GetMetadataResponse.component_metadata_result) +} + +// .mavsdk.rpc.component_metadata.MetadataData response = 2; +inline bool GetMetadataResponse::has_response() const { + bool value = (_impl_._has_bits_[0] & 0x00000002u) != 0; + PROTOBUF_ASSUME(!value || _impl_.response_ != nullptr); + return value; +} +inline void GetMetadataResponse::clear_response() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.response_ != nullptr) _impl_.response_->Clear(); + _impl_._has_bits_[0] &= ~0x00000002u; +} +inline const ::mavsdk::rpc::component_metadata::MetadataData& GetMetadataResponse::_internal_response() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::component_metadata::MetadataData* p = _impl_.response_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::component_metadata::_MetadataData_default_instance_); +} +inline const ::mavsdk::rpc::component_metadata::MetadataData& GetMetadataResponse::response() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.GetMetadataResponse.response) + return _internal_response(); +} +inline void GetMetadataResponse::unsafe_arena_set_allocated_response(::mavsdk::rpc::component_metadata::MetadataData* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.response_); + } + _impl_.response_ = reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataData*>(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.component_metadata.GetMetadataResponse.response) +} +inline ::mavsdk::rpc::component_metadata::MetadataData* GetMetadataResponse::release_response() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::component_metadata::MetadataData* released = _impl_.response_; + _impl_.response_ = 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::component_metadata::MetadataData* GetMetadataResponse::unsafe_arena_release_response() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_metadata.GetMetadataResponse.response) + + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::component_metadata::MetadataData* temp = _impl_.response_; + _impl_.response_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::component_metadata::MetadataData* GetMetadataResponse::_internal_mutable_response() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000002u; + if (_impl_.response_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::component_metadata::MetadataData>(GetArena()); + _impl_.response_ = reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataData*>(p); + } + return _impl_.response_; +} +inline ::mavsdk::rpc::component_metadata::MetadataData* GetMetadataResponse::mutable_response() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::component_metadata::MetadataData* _msg = _internal_mutable_response(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_metadata.GetMetadataResponse.response) + return _msg; +} +inline void GetMetadataResponse::set_allocated_response(::mavsdk::rpc::component_metadata::MetadataData* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataData*>(_impl_.response_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataData*>(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_.response_ = reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataData*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_metadata.GetMetadataResponse.response) +} + +// ------------------------------------------------------------------- + +// MetadataData + +// string json_metadata = 1; +inline void MetadataData::clear_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.json_metadata_.ClearToEmpty(); +} +inline const std::string& MetadataData::json_metadata() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.MetadataData.json_metadata) + return _internal_json_metadata(); +} +template +inline PROTOBUF_ALWAYS_INLINE void MetadataData::set_json_metadata(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.json_metadata_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata.MetadataData.json_metadata) +} +inline std::string* MetadataData::mutable_json_metadata() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_json_metadata(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_metadata.MetadataData.json_metadata) + return _s; +} +inline const std::string& MetadataData::_internal_json_metadata() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.json_metadata_.Get(); +} +inline void MetadataData::_internal_set_json_metadata(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.json_metadata_.Set(value, GetArena()); +} +inline std::string* MetadataData::_internal_mutable_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.json_metadata_.Mutable( GetArena()); +} +inline std::string* MetadataData::release_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_metadata.MetadataData.json_metadata) + return _impl_.json_metadata_.Release(); +} +inline void MetadataData::set_allocated_json_metadata(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.json_metadata_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.json_metadata_.IsDefault()) { + _impl_.json_metadata_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_metadata.MetadataData.json_metadata) +} + +// ------------------------------------------------------------------- + +// ComponentMetadataResult + +// .mavsdk.rpc.component_metadata.ComponentMetadataResult.Result result = 1; +inline void ComponentMetadataResult::clear_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.result_ = 0; +} +inline ::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result ComponentMetadataResult::result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.ComponentMetadataResult.result) + return _internal_result(); +} +inline void ComponentMetadataResult::set_result(::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result value) { + _internal_set_result(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata.ComponentMetadataResult.result) +} +inline ::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result ComponentMetadataResult::_internal_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result>(_impl_.result_); +} +inline void ComponentMetadataResult::_internal_set_result(::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.result_ = value; +} + +// string result_str = 2; +inline void ComponentMetadataResult::clear_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.result_str_.ClearToEmpty(); +} +inline const std::string& ComponentMetadataResult::result_str() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.ComponentMetadataResult.result_str) + return _internal_result_str(); +} +template +inline PROTOBUF_ALWAYS_INLINE void ComponentMetadataResult::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.component_metadata.ComponentMetadataResult.result_str) +} +inline std::string* ComponentMetadataResult::mutable_result_str() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_result_str(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_metadata.ComponentMetadataResult.result_str) + return _s; +} +inline const std::string& ComponentMetadataResult::_internal_result_str() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.result_str_.Get(); +} +inline void ComponentMetadataResult::_internal_set_result_str(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.result_str_.Set(value, GetArena()); +} +inline std::string* ComponentMetadataResult::_internal_mutable_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.result_str_.Mutable( GetArena()); +} +inline std::string* ComponentMetadataResult::release_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_metadata.ComponentMetadataResult.result_str) + return _impl_.result_str_.Release(); +} +inline void ComponentMetadataResult::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.component_metadata.ComponentMetadataResult.result_str) +} + +// ------------------------------------------------------------------- + +// RequestComponentResponse + +// ------------------------------------------------------------------- + +// RequestAutopilotComponentRequest + +// ------------------------------------------------------------------- + +// RequestAutopilotComponentResponse + +// ------------------------------------------------------------------- + +// SubscribeMetadataAvailableRequest + +// ------------------------------------------------------------------- + +// MetadataAvailableResponse + +// .mavsdk.rpc.component_metadata.MetadataUpdate data = 1; +inline bool MetadataAvailableResponse::has_data() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.data_ != nullptr); + return value; +} +inline void MetadataAvailableResponse::clear_data() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.data_ != nullptr) _impl_.data_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::component_metadata::MetadataUpdate& MetadataAvailableResponse::_internal_data() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::component_metadata::MetadataUpdate* p = _impl_.data_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::component_metadata::_MetadataUpdate_default_instance_); +} +inline const ::mavsdk::rpc::component_metadata::MetadataUpdate& MetadataAvailableResponse::data() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.MetadataAvailableResponse.data) + return _internal_data(); +} +inline void MetadataAvailableResponse::unsafe_arena_set_allocated_data(::mavsdk::rpc::component_metadata::MetadataUpdate* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.data_); + } + _impl_.data_ = reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataUpdate*>(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.component_metadata.MetadataAvailableResponse.data) +} +inline ::mavsdk::rpc::component_metadata::MetadataUpdate* MetadataAvailableResponse::release_data() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::component_metadata::MetadataUpdate* released = _impl_.data_; + _impl_.data_ = 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::component_metadata::MetadataUpdate* MetadataAvailableResponse::unsafe_arena_release_data() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_metadata.MetadataAvailableResponse.data) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::component_metadata::MetadataUpdate* temp = _impl_.data_; + _impl_.data_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::component_metadata::MetadataUpdate* MetadataAvailableResponse::_internal_mutable_data() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.data_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::component_metadata::MetadataUpdate>(GetArena()); + _impl_.data_ = reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataUpdate*>(p); + } + return _impl_.data_; +} +inline ::mavsdk::rpc::component_metadata::MetadataUpdate* MetadataAvailableResponse::mutable_data() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::component_metadata::MetadataUpdate* _msg = _internal_mutable_data(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_metadata.MetadataAvailableResponse.data) + return _msg; +} +inline void MetadataAvailableResponse::set_allocated_data(::mavsdk::rpc::component_metadata::MetadataUpdate* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataUpdate*>(_impl_.data_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataUpdate*>(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_.data_ = reinterpret_cast<::mavsdk::rpc::component_metadata::MetadataUpdate*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_metadata.MetadataAvailableResponse.data) +} + +// ------------------------------------------------------------------- + +// MetadataUpdate + +// uint32 compid = 1; +inline void MetadataUpdate::clear_compid() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.compid_ = 0u; +} +inline ::uint32_t MetadataUpdate::compid() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.MetadataUpdate.compid) + return _internal_compid(); +} +inline void MetadataUpdate::set_compid(::uint32_t value) { + _internal_set_compid(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata.MetadataUpdate.compid) +} +inline ::uint32_t MetadataUpdate::_internal_compid() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.compid_; +} +inline void MetadataUpdate::_internal_set_compid(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.compid_ = value; +} + +// .mavsdk.rpc.component_metadata.MetadataType type = 2; +inline void MetadataUpdate::clear_type() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.type_ = 0; +} +inline ::mavsdk::rpc::component_metadata::MetadataType MetadataUpdate::type() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.MetadataUpdate.type) + return _internal_type(); +} +inline void MetadataUpdate::set_type(::mavsdk::rpc::component_metadata::MetadataType value) { + _internal_set_type(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata.MetadataUpdate.type) +} +inline ::mavsdk::rpc::component_metadata::MetadataType MetadataUpdate::_internal_type() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::component_metadata::MetadataType>(_impl_.type_); +} +inline void MetadataUpdate::_internal_set_type(::mavsdk::rpc::component_metadata::MetadataType value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.type_ = value; +} + +// string json_metadata = 3; +inline void MetadataUpdate::clear_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.json_metadata_.ClearToEmpty(); +} +inline const std::string& MetadataUpdate::json_metadata() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata.MetadataUpdate.json_metadata) + return _internal_json_metadata(); +} +template +inline PROTOBUF_ALWAYS_INLINE void MetadataUpdate::set_json_metadata(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.json_metadata_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata.MetadataUpdate.json_metadata) +} +inline std::string* MetadataUpdate::mutable_json_metadata() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_json_metadata(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_metadata.MetadataUpdate.json_metadata) + return _s; +} +inline const std::string& MetadataUpdate::_internal_json_metadata() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.json_metadata_.Get(); +} +inline void MetadataUpdate::_internal_set_json_metadata(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.json_metadata_.Set(value, GetArena()); +} +inline std::string* MetadataUpdate::_internal_mutable_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.json_metadata_.Mutable( GetArena()); +} +inline std::string* MetadataUpdate::release_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_metadata.MetadataUpdate.json_metadata) + return _impl_.json_metadata_.Release(); +} +inline void MetadataUpdate::set_allocated_json_metadata(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.json_metadata_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.json_metadata_.IsDefault()) { + _impl_.json_metadata_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_metadata.MetadataUpdate.json_metadata) +} + +#ifdef __GNUC__ +#pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) +} // namespace component_metadata +} // namespace rpc +} // namespace mavsdk + + +namespace google { +namespace protobuf { + +template <> +struct is_proto_enum<::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result>() { + return ::mavsdk::rpc::component_metadata::ComponentMetadataResult_Result_descriptor(); +} +template <> +struct is_proto_enum<::mavsdk::rpc::component_metadata::MetadataType> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::component_metadata::MetadataType>() { + return ::mavsdk::rpc::component_metadata::MetadataType_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#include "google/protobuf/port_undef.inc" + +#endif // GOOGLE_PROTOBUF_INCLUDED_component_5fmetadata_2fcomponent_5fmetadata_2eproto_2epb_2eh diff --git a/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.grpc.pb.cc b/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.grpc.pb.cc new file mode 100644 index 0000000000..52ad288e3e --- /dev/null +++ b/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.grpc.pb.cc @@ -0,0 +1,90 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: component_metadata_server/component_metadata_server.proto + +#include "component_metadata_server/component_metadata_server.pb.h" +#include "component_metadata_server/component_metadata_server.grpc.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +namespace mavsdk { +namespace rpc { +namespace component_metadata_server { + +static const char* ComponentMetadataServerService_method_names[] = { + "/mavsdk.rpc.component_metadata_server.ComponentMetadataServerService/SetMetadata", +}; + +std::unique_ptr< ComponentMetadataServerService::Stub> ComponentMetadataServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { + (void)options; + std::unique_ptr< ComponentMetadataServerService::Stub> stub(new ComponentMetadataServerService::Stub(channel, options)); + return stub; +} + +ComponentMetadataServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) + : channel_(channel), rpcmethod_SetMetadata_(ComponentMetadataServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + {} + +::grpc::Status ComponentMetadataServerService::Stub::SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetMetadata_, context, request, response); +} + +void ComponentMetadataServerService::Stub::async::SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetMetadata_, context, request, response, std::move(f)); +} + +void ComponentMetadataServerService::Stub::async::SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetMetadata_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* ComponentMetadataServerService::Stub::PrepareAsyncSetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse, ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetMetadata_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* ComponentMetadataServerService::Stub::AsyncSetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncSetMetadataRaw(context, request, cq); + result->StartCall(); + return result; +} + +ComponentMetadataServerService::Service::Service() { + AddMethod(new ::grpc::internal::RpcServiceMethod( + ComponentMetadataServerService_method_names[0], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< ComponentMetadataServerService::Service, ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](ComponentMetadataServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* req, + ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* resp) { + return service->SetMetadata(ctx, req, resp); + }, this))); +} + +ComponentMetadataServerService::Service::~Service() { +} + +::grpc::Status ComponentMetadataServerService::Service::SetMetadata(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + + +} // namespace mavsdk +} // namespace rpc +} // namespace component_metadata_server + diff --git a/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.grpc.pb.h b/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.grpc.pb.h new file mode 100644 index 0000000000..a8f146b7f9 --- /dev/null +++ b/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.grpc.pb.h @@ -0,0 +1,251 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: component_metadata_server/component_metadata_server.proto +#ifndef GRPC_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto__INCLUDED +#define GRPC_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto__INCLUDED + +#include "component_metadata_server/component_metadata_server.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace rpc { +namespace component_metadata_server { + +// Provide component metadata json definitions, such as parameters. +class ComponentMetadataServerService final { + public: + static constexpr char const* service_full_name() { + return "mavsdk.rpc.component_metadata_server.ComponentMetadataServerService"; + } + class StubInterface { + public: + virtual ~StubInterface() {} + // + // Provide metadata (can only be called once) + virtual ::grpc::Status SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>> AsyncSetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>>(AsyncSetMetadataRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>> PrepareAsyncSetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>>(PrepareAsyncSetMetadataRaw(context, request, cq)); + } + class async_interface { + public: + virtual ~async_interface() {} + // + // Provide metadata (can only be called once) + virtual void SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response, std::function) = 0; + virtual void SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + }; + typedef class async_interface experimental_async_interface; + virtual class async_interface* async() { return nullptr; } + class async_interface* experimental_async() { return async(); } + private: + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* AsyncSetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* PrepareAsyncSetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) = 0; + }; + class Stub final : public StubInterface { + public: + Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + ::grpc::Status SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>> AsyncSetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>>(AsyncSetMetadataRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>> PrepareAsyncSetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>>(PrepareAsyncSetMetadataRaw(context, request, cq)); + } + class async final : + public StubInterface::async_interface { + public: + void SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response, std::function) override; + void SetMetadata(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + private: + friend class Stub; + explicit async(Stub* stub): stub_(stub) { } + Stub* stub() { return stub_; } + Stub* stub_; + }; + class async* async() override { return &async_stub_; } + + private: + std::shared_ptr< ::grpc::ChannelInterface> channel_; + class async async_stub_{this}; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* AsyncSetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* PrepareAsyncSetMetadataRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest& request, ::grpc::CompletionQueue* cq) override; + const ::grpc::internal::RpcMethod rpcmethod_SetMetadata_; + }; + 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(); + // + // Provide metadata (can only be called once) + virtual ::grpc::Status SetMetadata(::grpc::ServerContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response); + }; + template + class WithAsyncMethod_SetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SetMetadata() { + ::grpc::Service::MarkMethodAsync(0); + } + ~WithAsyncMethod_SetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetMetadata(::grpc::ServerContext* context, ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetMetadata AsyncService; + template + class WithCallbackMethod_SetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SetMetadata() { + ::grpc::Service::MarkMethodCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* request, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* response) { return this->SetMetadata(context, request, response); }));} + void SetMessageAllocatorFor_SetMetadata( + ::grpc::MessageAllocator< ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_SetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetMetadata( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetMetadata CallbackService; + typedef CallbackService ExperimentalCallbackService; + template + class WithGenericMethod_SetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetMetadata() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_SetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithRawMethod_SetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetMetadata() { + ::grpc::Service::MarkMethodRaw(0); + } + ~WithRawMethod_SetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetMetadata(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawCallbackMethod_SetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetMetadata() { + ::grpc::Service::MarkMethodRawCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetMetadata(context, request, response); })); + } + ~WithRawCallbackMethod_SetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetMetadata( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithStreamedUnaryMethod_SetMetadata : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_SetMetadata() { + ::grpc::Service::MarkMethodStreamed(0, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::component_metadata_server::SetMetadataRequest, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* streamer) { + return this->StreamedSetMetadata(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_SetMetadata() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SetMetadata(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_metadata_server::SetMetadataRequest* /*request*/, ::mavsdk::rpc::component_metadata_server::SetMetadataResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedSetMetadata(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::component_metadata_server::SetMetadataRequest,::mavsdk::rpc::component_metadata_server::SetMetadataResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_SetMetadata StreamedUnaryService; + typedef Service SplitStreamedService; + typedef WithStreamedUnaryMethod_SetMetadata StreamedService; +}; + +} // namespace component_metadata_server +} // namespace rpc +} // namespace mavsdk + + +#endif // GRPC_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto__INCLUDED diff --git a/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.pb.cc b/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.pb.cc new file mode 100644 index 0000000000..25c011de7f --- /dev/null +++ b/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.pb.cc @@ -0,0 +1,644 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: component_metadata_server/component_metadata_server.proto + +#include "component_metadata_server/component_metadata_server.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 component_metadata_server { + template +PROTOBUF_CONSTEXPR SetMetadataResponse::SetMetadataResponse(::_pbi::ConstantInitialized) {} +struct SetMetadataResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetMetadataResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetMetadataResponseDefaultTypeInternal() {} + union { + SetMetadataResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetMetadataResponseDefaultTypeInternal _SetMetadataResponse_default_instance_; + +inline constexpr Metadata::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : json_metadata_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + type_{static_cast< ::mavsdk::rpc::component_metadata_server::MetadataType >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR Metadata::Metadata(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct MetadataDefaultTypeInternal { + PROTOBUF_CONSTEXPR MetadataDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~MetadataDefaultTypeInternal() {} + union { + Metadata _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 MetadataDefaultTypeInternal _Metadata_default_instance_; + +inline constexpr SetMetadataRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : metadata_{}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR SetMetadataRequest::SetMetadataRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct SetMetadataRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetMetadataRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetMetadataRequestDefaultTypeInternal() {} + union { + SetMetadataRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetMetadataRequestDefaultTypeInternal _SetMetadataRequest_default_instance_; +} // namespace component_metadata_server +} // namespace rpc +} // namespace mavsdk +static ::_pb::Metadata file_level_metadata_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto[3]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto[1]; +static constexpr const ::_pb::ServiceDescriptor** + file_level_service_descriptors_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto = nullptr; +const ::uint32_t TableStruct_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( + protodesc_cold) = { + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata_server::SetMetadataRequest, _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::component_metadata_server::SetMetadataRequest, _impl_.metadata_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata_server::SetMetadataResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata_server::Metadata, _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::component_metadata_server::Metadata, _impl_.type_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata_server::Metadata, _impl_.json_metadata_), +}; + +static const ::_pbi::MigrationSchema + schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + {0, -1, -1, sizeof(::mavsdk::rpc::component_metadata_server::SetMetadataRequest)}, + {9, -1, -1, sizeof(::mavsdk::rpc::component_metadata_server::SetMetadataResponse)}, + {17, -1, -1, sizeof(::mavsdk::rpc::component_metadata_server::Metadata)}, +}; + +static const ::_pb::Message* const file_default_instances[] = { + &::mavsdk::rpc::component_metadata_server::_SetMetadataRequest_default_instance_._instance, + &::mavsdk::rpc::component_metadata_server::_SetMetadataResponse_default_instance_._instance, + &::mavsdk::rpc::component_metadata_server::_Metadata_default_instance_._instance, +}; +const char descriptor_table_protodef_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + "\n9component_metadata_server/component_me" + "tadata_server.proto\022$mavsdk.rpc.componen" + "t_metadata_server\032\024mavsdk_options.proto\"" + "V\n\022SetMetadataRequest\022@\n\010metadata\030\001 \003(\0132" + "..mavsdk.rpc.component_metadata_server.M" + "etadata\"\025\n\023SetMetadataResponse\"c\n\010Metada" + "ta\022@\n\004type\030\001 \001(\01622.mavsdk.rpc.component_" + "metadata_server.MetadataType\022\025\n\rjson_met" + "adata\030\002 \001(\t*b\n\014MetadataType\022\033\n\027METADATA_" + "TYPE_PARAMETER\020\000\022\030\n\024METADATA_TYPE_EVENTS" + "\020\001\022\033\n\027METADATA_TYPE_ACTUATORS\020\0022\253\001\n\036Comp" + "onentMetadataServerService\022\210\001\n\013SetMetada" + "ta\0228.mavsdk.rpc.component_metadata_serve" + "r.SetMetadataRequest\0329.mavsdk.rpc.compon" + "ent_metadata_server.SetMetadataResponse\"" + "\004\200\265\030\001BC\n#io.mavsdk.component_metadata_se" + "rverB\034ComponentMetadataServerProtob\006prot" + "o3" +}; +static const ::_pbi::DescriptorTable* const descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_deps[1] = + { + &::descriptor_table_mavsdk_5foptions_2eproto, +}; +static ::absl::once_flag descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_once; +const ::_pbi::DescriptorTable descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto = { + false, + false, + 682, + descriptor_table_protodef_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto, + "component_metadata_server/component_metadata_server.proto", + &descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_once, + descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_deps, + 1, + 3, + schemas, + file_default_instances, + TableStruct_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto::offsets, + file_level_metadata_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto, + file_level_enum_descriptors_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto, + file_level_service_descriptors_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_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_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_getter() { + return &descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto; +} +// Force running AddDescriptors() at dynamic initialization time. +PROTOBUF_ATTRIBUTE_INIT_PRIORITY2 +static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto(&descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto); +namespace mavsdk { +namespace rpc { +namespace component_metadata_server { +const ::google::protobuf::EnumDescriptor* MetadataType_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto); + return file_level_enum_descriptors_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto[0]; +} +PROTOBUF_CONSTINIT const uint32_t MetadataType_internal_data_[] = { + 196608u, 0u, }; +bool MetadataType_IsValid(int value) { + return 0 <= value && value <= 2; +} +// =================================================================== + +class SetMetadataRequest::_Internal { + public: +}; + +SetMetadataRequest::SetMetadataRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata_server.SetMetadataRequest) +} +inline PROTOBUF_NDEBUG_INLINE SetMetadataRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : metadata_{visibility, arena, from.metadata_}, + _cached_size_{0} {} + +SetMetadataRequest::SetMetadataRequest( + ::google::protobuf::Arena* arena, + const SetMetadataRequest& from) + : ::google::protobuf::Message(arena) { + SetMetadataRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata_server.SetMetadataRequest) +} +inline PROTOBUF_NDEBUG_INLINE SetMetadataRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : metadata_{visibility, arena}, + _cached_size_{0} {} + +inline void SetMetadataRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); +} +SetMetadataRequest::~SetMetadataRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata_server.SetMetadataRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void SetMetadataRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void SetMetadataRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata_server.SetMetadataRequest) + 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_.metadata_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* SetMetadataRequest::_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> SetMetadataRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_SetMetadataRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // repeated .mavsdk.rpc.component_metadata_server.Metadata metadata = 1; + {::_pbi::TcParser::FastMtR1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(SetMetadataRequest, _impl_.metadata_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // repeated .mavsdk.rpc.component_metadata_server.Metadata metadata = 1; + {PROTOBUF_FIELD_OFFSET(SetMetadataRequest, _impl_.metadata_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_metadata_server::Metadata>()}, + }}, {{ + }}, +}; + +::uint8_t* SetMetadataRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata_server.SetMetadataRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // repeated .mavsdk.rpc.component_metadata_server.Metadata metadata = 1; + for (unsigned i = 0, + n = static_cast(this->_internal_metadata_size()); i < n; i++) { + const auto& repfield = this->_internal_metadata().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(1, 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.component_metadata_server.SetMetadataRequest) + return target; +} + +::size_t SetMetadataRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata_server.SetMetadataRequest) + ::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.component_metadata_server.Metadata metadata = 1; + total_size += 1UL * this->_internal_metadata_size(); + for (const auto& msg : this->_internal_metadata()) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData SetMetadataRequest::_class_data_ = { + SetMetadataRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* SetMetadataRequest::GetClassData() const { + return &_class_data_; +} + +void SetMetadataRequest::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.component_metadata_server.SetMetadataRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + _this->_internal_mutable_metadata()->MergeFrom( + from._internal_metadata()); + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void SetMetadataRequest::CopyFrom(const SetMetadataRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata_server.SetMetadataRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool SetMetadataRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* SetMetadataRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void SetMetadataRequest::InternalSwap(SetMetadataRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + _impl_.metadata_.InternalSwap(&other->_impl_.metadata_); +} + +::google::protobuf::Metadata SetMetadataRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_getter, &descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_once, + file_level_metadata_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto[0]); +} +// =================================================================== + +class SetMetadataResponse::_Internal { + public: +}; + +SetMetadataResponse::SetMetadataResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata_server.SetMetadataResponse) +} +SetMetadataResponse::SetMetadataResponse( + ::google::protobuf::Arena* arena, + const SetMetadataResponse& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SetMetadataResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata_server.SetMetadataResponse) +} + + + + + + + + + +::google::protobuf::Metadata SetMetadataResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_getter, &descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_once, + file_level_metadata_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto[1]); +} +// =================================================================== + +class Metadata::_Internal { + public: +}; + +Metadata::Metadata(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata_server.Metadata) +} +inline PROTOBUF_NDEBUG_INLINE Metadata::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : json_metadata_(arena, from.json_metadata_), + _cached_size_{0} {} + +Metadata::Metadata( + ::google::protobuf::Arena* arena, + const Metadata& from) + : ::google::protobuf::Message(arena) { + Metadata* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + _impl_.type_ = from._impl_.type_; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata_server.Metadata) +} +inline PROTOBUF_NDEBUG_INLINE Metadata::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : json_metadata_(arena), + _cached_size_{0} {} + +inline void Metadata::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.type_ = {}; +} +Metadata::~Metadata() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_metadata_server.Metadata) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void Metadata::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.json_metadata_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void Metadata::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_metadata_server.Metadata) + 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_.json_metadata_.ClearToEmpty(); + _impl_.type_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* Metadata::_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, 67, 2> Metadata::_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 + &_Metadata_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // string json_metadata = 2; + {::_pbi::TcParser::FastUS1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(Metadata, _impl_.json_metadata_)}}, + // .mavsdk.rpc.component_metadata_server.MetadataType type = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Metadata, _impl_.type_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(Metadata, _impl_.type_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.component_metadata_server.MetadataType type = 1; + {PROTOBUF_FIELD_OFFSET(Metadata, _impl_.type_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + // string json_metadata = 2; + {PROTOBUF_FIELD_OFFSET(Metadata, _impl_.json_metadata_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\55\0\15\0\0\0\0\0" + "mavsdk.rpc.component_metadata_server.Metadata" + "json_metadata" + }}, +}; + +::uint8_t* Metadata::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_metadata_server.Metadata) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // .mavsdk.rpc.component_metadata_server.MetadataType type = 1; + if (this->_internal_type() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_type(), target); + } + + // string json_metadata = 2; + if (!this->_internal_json_metadata().empty()) { + const std::string& _s = this->_internal_json_metadata(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_metadata_server.Metadata.json_metadata"); + 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.component_metadata_server.Metadata) + return target; +} + +::size_t Metadata::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_metadata_server.Metadata) + ::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 json_metadata = 2; + if (!this->_internal_json_metadata().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_json_metadata()); + } + + // .mavsdk.rpc.component_metadata_server.MetadataType type = 1; + if (this->_internal_type() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_type()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData Metadata::_class_data_ = { + Metadata::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* Metadata::GetClassData() const { + return &_class_data_; +} + +void Metadata::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.component_metadata_server.Metadata) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_json_metadata().empty()) { + _this->_internal_set_json_metadata(from._internal_json_metadata()); + } + if (from._internal_type() != 0) { + _this->_internal_set_type(from._internal_type()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void Metadata::CopyFrom(const Metadata& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_metadata_server.Metadata) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool Metadata::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* Metadata::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void Metadata::InternalSwap(Metadata* 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_.json_metadata_, &other->_impl_.json_metadata_, arena); + swap(_impl_.type_, other->_impl_.type_); +} + +::google::protobuf::Metadata Metadata::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_getter, &descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_once, + file_level_metadata_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto[2]); +} +// @@protoc_insertion_point(namespace_scope) +} // namespace component_metadata_server +} // 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/component_metadata_server/component_metadata_server.pb.h b/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.pb.h new file mode 100644 index 0000000000..d31e8afc87 --- /dev/null +++ b/src/mavsdk_server/src/generated/component_metadata_server/component_metadata_server.pb.h @@ -0,0 +1,812 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: component_metadata_server/component_metadata_server.proto +// Protobuf C++ Version: 4.25.1 + +#ifndef GOOGLE_PROTOBUF_INCLUDED_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_2epb_2eh +#define GOOGLE_PROTOBUF_INCLUDED_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_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_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_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_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto { + static const ::uint32_t offsets[]; +}; +extern const ::google::protobuf::internal::DescriptorTable + descriptor_table_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto; +namespace mavsdk { +namespace rpc { +namespace component_metadata_server { +class Metadata; +struct MetadataDefaultTypeInternal; +extern MetadataDefaultTypeInternal _Metadata_default_instance_; +class SetMetadataRequest; +struct SetMetadataRequestDefaultTypeInternal; +extern SetMetadataRequestDefaultTypeInternal _SetMetadataRequest_default_instance_; +class SetMetadataResponse; +struct SetMetadataResponseDefaultTypeInternal; +extern SetMetadataResponseDefaultTypeInternal _SetMetadataResponse_default_instance_; +} // namespace component_metadata_server +} // namespace rpc +} // namespace mavsdk +namespace google { +namespace protobuf { +} // namespace protobuf +} // namespace google + +namespace mavsdk { +namespace rpc { +namespace component_metadata_server { +enum MetadataType : int { + METADATA_TYPE_PARAMETER = 0, + METADATA_TYPE_EVENTS = 1, + METADATA_TYPE_ACTUATORS = 2, + MetadataType_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + MetadataType_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool MetadataType_IsValid(int value); +extern const uint32_t MetadataType_internal_data_[]; +constexpr MetadataType MetadataType_MIN = static_cast(0); +constexpr MetadataType MetadataType_MAX = static_cast(2); +constexpr int MetadataType_ARRAYSIZE = 2 + 1; +const ::google::protobuf::EnumDescriptor* +MetadataType_descriptor(); +template +const std::string& MetadataType_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to MetadataType_Name()."); + return MetadataType_Name(static_cast(value)); +} +template <> +inline const std::string& MetadataType_Name(MetadataType value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool MetadataType_Parse(absl::string_view name, MetadataType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + MetadataType_descriptor(), name, value); +} + +// =================================================================== + + +// ------------------------------------------------------------------- + +class SetMetadataResponse final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata_server.SetMetadataResponse) */ { + public: + inline SetMetadataResponse() : SetMetadataResponse(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SetMetadataResponse(::google::protobuf::internal::ConstantInitialized); + + inline SetMetadataResponse(const SetMetadataResponse& from) + : SetMetadataResponse(nullptr, from) {} + SetMetadataResponse(SetMetadataResponse&& from) noexcept + : SetMetadataResponse() { + *this = ::std::move(from); + } + + inline SetMetadataResponse& operator=(const SetMetadataResponse& from) { + CopyFrom(from); + return *this; + } + inline SetMetadataResponse& operator=(SetMetadataResponse&& 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 SetMetadataResponse& default_instance() { + return *internal_default_instance(); + } + static inline const SetMetadataResponse* internal_default_instance() { + return reinterpret_cast( + &_SetMetadataResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + friend void swap(SetMetadataResponse& a, SetMetadataResponse& b) { + a.Swap(&b); + } + inline void Swap(SetMetadataResponse* 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(SetMetadataResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetMetadataResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SetMetadataResponse& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SetMetadataResponse& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata_server.SetMetadataResponse"; + } + protected: + explicit SetMetadataResponse(::google::protobuf::Arena* arena); + SetMetadataResponse(::google::protobuf::Arena* arena, const SetMetadataResponse& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata_server.SetMetadataResponse) + 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_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class Metadata final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata_server.Metadata) */ { + public: + inline Metadata() : Metadata(nullptr) {} + ~Metadata() override; + template + explicit PROTOBUF_CONSTEXPR Metadata(::google::protobuf::internal::ConstantInitialized); + + inline Metadata(const Metadata& from) + : Metadata(nullptr, from) {} + Metadata(Metadata&& from) noexcept + : Metadata() { + *this = ::std::move(from); + } + + inline Metadata& operator=(const Metadata& from) { + CopyFrom(from); + return *this; + } + inline Metadata& operator=(Metadata&& 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 Metadata& default_instance() { + return *internal_default_instance(); + } + static inline const Metadata* internal_default_instance() { + return reinterpret_cast( + &_Metadata_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(Metadata& a, Metadata& b) { + a.Swap(&b); + } + inline void Swap(Metadata* 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(Metadata* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Metadata* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const Metadata& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const Metadata& from) { + Metadata::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(Metadata* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata_server.Metadata"; + } + protected: + explicit Metadata(::google::protobuf::Arena* arena); + Metadata(::google::protobuf::Arena* arena, const Metadata& 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 { + kJsonMetadataFieldNumber = 2, + kTypeFieldNumber = 1, + }; + // string json_metadata = 2; + void clear_json_metadata() ; + const std::string& json_metadata() const; + template + void set_json_metadata(Arg_&& arg, Args_... args); + std::string* mutable_json_metadata(); + PROTOBUF_NODISCARD std::string* release_json_metadata(); + void set_allocated_json_metadata(std::string* value); + + private: + const std::string& _internal_json_metadata() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_json_metadata( + const std::string& value); + std::string* _internal_mutable_json_metadata(); + + public: + // .mavsdk.rpc.component_metadata_server.MetadataType type = 1; + void clear_type() ; + ::mavsdk::rpc::component_metadata_server::MetadataType type() const; + void set_type(::mavsdk::rpc::component_metadata_server::MetadataType value); + + private: + ::mavsdk::rpc::component_metadata_server::MetadataType _internal_type() const; + void _internal_set_type(::mavsdk::rpc::component_metadata_server::MetadataType value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata_server.Metadata) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 0, + 67, 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 json_metadata_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SetMetadataRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_metadata_server.SetMetadataRequest) */ { + public: + inline SetMetadataRequest() : SetMetadataRequest(nullptr) {} + ~SetMetadataRequest() override; + template + explicit PROTOBUF_CONSTEXPR SetMetadataRequest(::google::protobuf::internal::ConstantInitialized); + + inline SetMetadataRequest(const SetMetadataRequest& from) + : SetMetadataRequest(nullptr, from) {} + SetMetadataRequest(SetMetadataRequest&& from) noexcept + : SetMetadataRequest() { + *this = ::std::move(from); + } + + inline SetMetadataRequest& operator=(const SetMetadataRequest& from) { + CopyFrom(from); + return *this; + } + inline SetMetadataRequest& operator=(SetMetadataRequest&& 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 SetMetadataRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetMetadataRequest* internal_default_instance() { + return reinterpret_cast( + &_SetMetadataRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + friend void swap(SetMetadataRequest& a, SetMetadataRequest& b) { + a.Swap(&b); + } + inline void Swap(SetMetadataRequest* 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(SetMetadataRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetMetadataRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const SetMetadataRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const SetMetadataRequest& from) { + SetMetadataRequest::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(SetMetadataRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.component_metadata_server.SetMetadataRequest"; + } + protected: + explicit SetMetadataRequest(::google::protobuf::Arena* arena); + SetMetadataRequest(::google::protobuf::Arena* arena, const SetMetadataRequest& 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 { + kMetadataFieldNumber = 1, + }; + // repeated .mavsdk.rpc.component_metadata_server.Metadata metadata = 1; + int metadata_size() const; + private: + int _internal_metadata_size() const; + + public: + void clear_metadata() ; + ::mavsdk::rpc::component_metadata_server::Metadata* mutable_metadata(int index); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::component_metadata_server::Metadata >* + mutable_metadata(); + private: + const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_metadata_server::Metadata>& _internal_metadata() const; + ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_metadata_server::Metadata>* _internal_mutable_metadata(); + public: + const ::mavsdk::rpc::component_metadata_server::Metadata& metadata(int index) const; + ::mavsdk::rpc::component_metadata_server::Metadata* add_metadata(); + const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::component_metadata_server::Metadata >& + metadata() const; + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_metadata_server.SetMetadataRequest) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::component_metadata_server::Metadata > metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto; +}; + +// =================================================================== + + + + +// =================================================================== + + +#ifdef __GNUC__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// SetMetadataRequest + +// repeated .mavsdk.rpc.component_metadata_server.Metadata metadata = 1; +inline int SetMetadataRequest::_internal_metadata_size() const { + return _internal_metadata().size(); +} +inline int SetMetadataRequest::metadata_size() const { + return _internal_metadata_size(); +} +inline void SetMetadataRequest::clear_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.metadata_.Clear(); +} +inline ::mavsdk::rpc::component_metadata_server::Metadata* SetMetadataRequest::mutable_metadata(int index) + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_metadata_server.SetMetadataRequest.metadata) + return _internal_mutable_metadata()->Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_metadata_server::Metadata>* SetMetadataRequest::mutable_metadata() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.component_metadata_server.SetMetadataRequest.metadata) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_metadata(); +} +inline const ::mavsdk::rpc::component_metadata_server::Metadata& SetMetadataRequest::metadata(int index) const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata_server.SetMetadataRequest.metadata) + return _internal_metadata().Get(index); +} +inline ::mavsdk::rpc::component_metadata_server::Metadata* SetMetadataRequest::add_metadata() ABSL_ATTRIBUTE_LIFETIME_BOUND { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::mavsdk::rpc::component_metadata_server::Metadata* _add = _internal_mutable_metadata()->Add(); + // @@protoc_insertion_point(field_add:mavsdk.rpc.component_metadata_server.SetMetadataRequest.metadata) + return _add; +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_metadata_server::Metadata>& SetMetadataRequest::metadata() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.component_metadata_server.SetMetadataRequest.metadata) + return _internal_metadata(); +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_metadata_server::Metadata>& +SetMetadataRequest::_internal_metadata() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.metadata_; +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_metadata_server::Metadata>* +SetMetadataRequest::_internal_mutable_metadata() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.metadata_; +} + +// ------------------------------------------------------------------- + +// SetMetadataResponse + +// ------------------------------------------------------------------- + +// Metadata + +// .mavsdk.rpc.component_metadata_server.MetadataType type = 1; +inline void Metadata::clear_type() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.type_ = 0; +} +inline ::mavsdk::rpc::component_metadata_server::MetadataType Metadata::type() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata_server.Metadata.type) + return _internal_type(); +} +inline void Metadata::set_type(::mavsdk::rpc::component_metadata_server::MetadataType value) { + _internal_set_type(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata_server.Metadata.type) +} +inline ::mavsdk::rpc::component_metadata_server::MetadataType Metadata::_internal_type() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::component_metadata_server::MetadataType>(_impl_.type_); +} +inline void Metadata::_internal_set_type(::mavsdk::rpc::component_metadata_server::MetadataType value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.type_ = value; +} + +// string json_metadata = 2; +inline void Metadata::clear_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.json_metadata_.ClearToEmpty(); +} +inline const std::string& Metadata::json_metadata() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_metadata_server.Metadata.json_metadata) + return _internal_json_metadata(); +} +template +inline PROTOBUF_ALWAYS_INLINE void Metadata::set_json_metadata(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.json_metadata_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_metadata_server.Metadata.json_metadata) +} +inline std::string* Metadata::mutable_json_metadata() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_json_metadata(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_metadata_server.Metadata.json_metadata) + return _s; +} +inline const std::string& Metadata::_internal_json_metadata() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.json_metadata_.Get(); +} +inline void Metadata::_internal_set_json_metadata(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.json_metadata_.Set(value, GetArena()); +} +inline std::string* Metadata::_internal_mutable_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.json_metadata_.Mutable( GetArena()); +} +inline std::string* Metadata::release_json_metadata() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_metadata_server.Metadata.json_metadata) + return _impl_.json_metadata_.Release(); +} +inline void Metadata::set_allocated_json_metadata(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.json_metadata_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.json_metadata_.IsDefault()) { + _impl_.json_metadata_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_metadata_server.Metadata.json_metadata) +} + +#ifdef __GNUC__ +#pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) +} // namespace component_metadata_server +} // namespace rpc +} // namespace mavsdk + + +namespace google { +namespace protobuf { + +template <> +struct is_proto_enum<::mavsdk::rpc::component_metadata_server::MetadataType> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::component_metadata_server::MetadataType>() { + return ::mavsdk::rpc::component_metadata_server::MetadataType_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#include "google/protobuf/port_undef.inc" + +#endif // GOOGLE_PROTOBUF_INCLUDED_component_5fmetadata_5fserver_2fcomponent_5fmetadata_5fserver_2eproto_2epb_2eh diff --git a/src/mavsdk_server/src/grpc_server.cpp b/src/mavsdk_server/src/grpc_server.cpp index 5e964e636a..85d611a489 100644 --- a/src/mavsdk_server/src/grpc_server.cpp +++ b/src/mavsdk_server/src/grpc_server.cpp @@ -46,12 +46,12 @@ int GrpcServer::run() builder.RegisterService(&_camera_server_service); #endif -#ifdef COMPONENT_INFORMATION_ENABLED - builder.RegisterService(&_component_information_service); +#ifdef COMPONENT_METADATA_ENABLED + builder.RegisterService(&_component_metadata_service); #endif -#ifdef COMPONENT_INFORMATION_SERVER_ENABLED - builder.RegisterService(&_component_information_server_service); +#ifdef COMPONENT_METADATA_SERVER_ENABLED + builder.RegisterService(&_component_metadata_server_service); #endif #ifdef FAILURE_ENABLED @@ -213,12 +213,12 @@ void GrpcServer::stop() _camera_server_service.stop(); #endif -#ifdef COMPONENT_INFORMATION_ENABLED - _component_information_service.stop(); +#ifdef COMPONENT_METADATA_ENABLED + _component_metadata_service.stop(); #endif -#ifdef COMPONENT_INFORMATION_SERVER_ENABLED - _component_information_server_service.stop(); +#ifdef COMPONENT_METADATA_SERVER_ENABLED + _component_metadata_server_service.stop(); #endif #ifdef FAILURE_ENABLED diff --git a/src/mavsdk_server/src/grpc_server.h b/src/mavsdk_server/src/grpc_server.h index bf4af946e3..df0f8f52e8 100644 --- a/src/mavsdk_server/src/grpc_server.h +++ b/src/mavsdk_server/src/grpc_server.h @@ -44,14 +44,14 @@ #include "camera_server/camera_server_service_impl.h" #endif -#ifdef COMPONENT_INFORMATION_ENABLED -#include "plugins/component_information/component_information.h" -#include "component_information/component_information_service_impl.h" +#ifdef COMPONENT_METADATA_ENABLED +#include "plugins/component_metadata/component_metadata.h" +#include "component_metadata/component_metadata_service_impl.h" #endif -#ifdef COMPONENT_INFORMATION_SERVER_ENABLED -#include "plugins/component_information_server/component_information_server.h" -#include "component_information_server/component_information_server_service_impl.h" +#ifdef COMPONENT_METADATA_SERVER_ENABLED +#include "plugins/component_metadata_server/component_metadata_server.h" +#include "component_metadata_server/component_metadata_server_service_impl.h" #endif #ifdef FAILURE_ENABLED @@ -222,14 +222,14 @@ class GrpcServer { _camera_server_service(_camera_server_lazy_plugin), #endif -#ifdef COMPONENT_INFORMATION_ENABLED - _component_information_lazy_plugin(mavsdk), - _component_information_service(_component_information_lazy_plugin), +#ifdef COMPONENT_METADATA_ENABLED + _component_metadata_lazy_plugin(mavsdk), + _component_metadata_service(_component_metadata_lazy_plugin), #endif -#ifdef COMPONENT_INFORMATION_SERVER_ENABLED - _component_information_server_lazy_plugin(mavsdk), - _component_information_server_service(_component_information_server_lazy_plugin), +#ifdef COMPONENT_METADATA_SERVER_ENABLED + _component_metadata_server_lazy_plugin(mavsdk), + _component_metadata_server_service(_component_metadata_server_lazy_plugin), #endif #ifdef FAILURE_ENABLED @@ -416,18 +416,18 @@ class GrpcServer { CameraServerServiceImpl<> _camera_server_service; #endif -#ifdef COMPONENT_INFORMATION_ENABLED +#ifdef COMPONENT_METADATA_ENABLED - LazyPlugin _component_information_lazy_plugin; + LazyPlugin _component_metadata_lazy_plugin; - ComponentInformationServiceImpl<> _component_information_service; + ComponentMetadataServiceImpl<> _component_metadata_service; #endif -#ifdef COMPONENT_INFORMATION_SERVER_ENABLED +#ifdef COMPONENT_METADATA_SERVER_ENABLED - LazyServerPlugin _component_information_server_lazy_plugin; + LazyServerPlugin _component_metadata_server_lazy_plugin; - ComponentInformationServerServiceImpl<> _component_information_server_service; + ComponentMetadataServerServiceImpl<> _component_metadata_server_service; #endif #ifdef FAILURE_ENABLED diff --git a/src/mavsdk_server/src/plugins/component_metadata/component_metadata_service_impl.h b/src/mavsdk_server/src/plugins/component_metadata/component_metadata_service_impl.h new file mode 100644 index 0000000000..45839657aa --- /dev/null +++ b/src/mavsdk_server/src/plugins/component_metadata/component_metadata_service_impl.h @@ -0,0 +1,339 @@ +// 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/component_metadata/component_metadata.proto) + +#include "component_metadata/component_metadata.grpc.pb.h" +#include "plugins/component_metadata/component_metadata.h" + +#include "mavsdk.h" + +#include "lazy_plugin.h" + +#include "log.h" +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace mavsdk_server { + +template< + typename ComponentMetadata = ComponentMetadata, + typename LazyPlugin = LazyPlugin> + +class ComponentMetadataServiceImpl final + : public rpc::component_metadata::ComponentMetadataService::Service { +public: + ComponentMetadataServiceImpl(LazyPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) {} + + template + void + fillResponseWithResult(ResponseType* response, mavsdk::ComponentMetadata::Result& result) const + { + auto rpc_result = translateToRpcResult(result); + + auto* rpc_component_metadata_result = + new rpc::component_metadata::ComponentMetadataResult(); + rpc_component_metadata_result->set_result(rpc_result); + std::stringstream ss; + ss << result; + rpc_component_metadata_result->set_result_str(ss.str()); + + response->set_allocated_component_metadata_result(rpc_component_metadata_result); + } + + static rpc::component_metadata::MetadataType + translateToRpcMetadataType(const mavsdk::ComponentMetadata::MetadataType& metadata_type) + { + switch (metadata_type) { + default: + LogErr() << "Unknown metadata_type enum value: " << static_cast(metadata_type); + // FALLTHROUGH + case mavsdk::ComponentMetadata::MetadataType::AllCompleted: + return rpc::component_metadata::METADATA_TYPE_ALL_COMPLETED; + case mavsdk::ComponentMetadata::MetadataType::Parameter: + return rpc::component_metadata::METADATA_TYPE_PARAMETER; + case mavsdk::ComponentMetadata::MetadataType::Events: + return rpc::component_metadata::METADATA_TYPE_EVENTS; + case mavsdk::ComponentMetadata::MetadataType::Actuators: + return rpc::component_metadata::METADATA_TYPE_ACTUATORS; + } + } + + static mavsdk::ComponentMetadata::MetadataType + translateFromRpcMetadataType(const rpc::component_metadata::MetadataType metadata_type) + { + switch (metadata_type) { + default: + LogErr() << "Unknown metadata_type enum value: " << static_cast(metadata_type); + // FALLTHROUGH + case rpc::component_metadata::METADATA_TYPE_ALL_COMPLETED: + return mavsdk::ComponentMetadata::MetadataType::AllCompleted; + case rpc::component_metadata::METADATA_TYPE_PARAMETER: + return mavsdk::ComponentMetadata::MetadataType::Parameter; + case rpc::component_metadata::METADATA_TYPE_EVENTS: + return mavsdk::ComponentMetadata::MetadataType::Events; + case rpc::component_metadata::METADATA_TYPE_ACTUATORS: + return mavsdk::ComponentMetadata::MetadataType::Actuators; + } + } + + static std::unique_ptr + translateToRpcMetadataData(const mavsdk::ComponentMetadata::MetadataData& metadata_data) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_json_metadata(metadata_data.json_metadata); + + return rpc_obj; + } + + static mavsdk::ComponentMetadata::MetadataData + translateFromRpcMetadataData(const rpc::component_metadata::MetadataData& metadata_data) + { + mavsdk::ComponentMetadata::MetadataData obj; + + obj.json_metadata = metadata_data.json_metadata(); + + return obj; + } + + static rpc::component_metadata::ComponentMetadataResult::Result + translateToRpcResult(const mavsdk::ComponentMetadata::Result& result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case mavsdk::ComponentMetadata::Result::Success: + return rpc::component_metadata::ComponentMetadataResult_Result_RESULT_SUCCESS; + case mavsdk::ComponentMetadata::Result::NotAvailable: + return rpc::component_metadata::ComponentMetadataResult_Result_RESULT_NOT_AVAILABLE; + case mavsdk::ComponentMetadata::Result::ConnectionError: + return rpc::component_metadata:: + ComponentMetadataResult_Result_RESULT_CONNECTION_ERROR; + case mavsdk::ComponentMetadata::Result::Unsupported: + return rpc::component_metadata::ComponentMetadataResult_Result_RESULT_UNSUPPORTED; + case mavsdk::ComponentMetadata::Result::Denied: + return rpc::component_metadata::ComponentMetadataResult_Result_RESULT_DENIED; + case mavsdk::ComponentMetadata::Result::Failed: + return rpc::component_metadata::ComponentMetadataResult_Result_RESULT_FAILED; + case mavsdk::ComponentMetadata::Result::Timeout: + return rpc::component_metadata::ComponentMetadataResult_Result_RESULT_TIMEOUT; + case mavsdk::ComponentMetadata::Result::NoSystem: + return rpc::component_metadata::ComponentMetadataResult_Result_RESULT_NO_SYSTEM; + case mavsdk::ComponentMetadata::Result::NotRequested: + return rpc::component_metadata::ComponentMetadataResult_Result_RESULT_NOT_REQUESTED; + } + } + + static mavsdk::ComponentMetadata::Result + translateFromRpcResult(const rpc::component_metadata::ComponentMetadataResult::Result result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_SUCCESS: + return mavsdk::ComponentMetadata::Result::Success; + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_NOT_AVAILABLE: + return mavsdk::ComponentMetadata::Result::NotAvailable; + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_CONNECTION_ERROR: + return mavsdk::ComponentMetadata::Result::ConnectionError; + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_UNSUPPORTED: + return mavsdk::ComponentMetadata::Result::Unsupported; + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_DENIED: + return mavsdk::ComponentMetadata::Result::Denied; + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_FAILED: + return mavsdk::ComponentMetadata::Result::Failed; + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_TIMEOUT: + return mavsdk::ComponentMetadata::Result::Timeout; + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_NO_SYSTEM: + return mavsdk::ComponentMetadata::Result::NoSystem; + case rpc::component_metadata::ComponentMetadataResult_Result_RESULT_NOT_REQUESTED: + return mavsdk::ComponentMetadata::Result::NotRequested; + } + } + + static std::unique_ptr + translateToRpcMetadataUpdate(const mavsdk::ComponentMetadata::MetadataUpdate& metadata_update) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_compid(metadata_update.compid); + + rpc_obj->set_type(translateToRpcMetadataType(metadata_update.type)); + + rpc_obj->set_json_metadata(metadata_update.json_metadata); + + return rpc_obj; + } + + static mavsdk::ComponentMetadata::MetadataUpdate + translateFromRpcMetadataUpdate(const rpc::component_metadata::MetadataUpdate& metadata_update) + { + mavsdk::ComponentMetadata::MetadataUpdate obj; + + obj.compid = metadata_update.compid(); + + obj.type = translateFromRpcMetadataType(metadata_update.type()); + + obj.json_metadata = metadata_update.json_metadata(); + + return obj; + } + + grpc::Status RequestComponent( + grpc::ServerContext* /* context */, + const rpc::component_metadata::RequestComponentRequest* request, + rpc::component_metadata::RequestComponentResponse* /* response */) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RequestComponent sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + _lazy_plugin.maybe_plugin()->request_component(request->compid()); + + return grpc::Status::OK; + } + + grpc::Status RequestAutopilotComponent( + grpc::ServerContext* /* context */, + const rpc::component_metadata::RequestAutopilotComponentRequest* /* request */, + rpc::component_metadata::RequestAutopilotComponentResponse* /* response */) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + _lazy_plugin.maybe_plugin()->request_autopilot_component(); + + return grpc::Status::OK; + } + + grpc::Status SubscribeMetadataAvailable( + grpc::ServerContext* /* context */, + const mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest* /* 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::ComponentMetadata::MetadataAvailableHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_metadata_available( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::ComponentMetadata::MetadataUpdate metadata_available) { + rpc::component_metadata::MetadataAvailableResponse rpc_response; + + rpc_response.set_allocated_data( + translateToRpcMetadataUpdate(metadata_available).release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_metadata_available(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 GetMetadata( + grpc::ServerContext* /* context */, + const rpc::component_metadata::GetMetadataRequest* request, + rpc::component_metadata::GetMetadataResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::ComponentMetadata::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "GetMetadata sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->get_metadata( + request->compid(), translateFromRpcMetadataType(request->metadata_type())); + + if (response != nullptr) { + fillResponseWithResult(response, result.first); + + response->set_allocated_response(translateToRpcMetadataData(result.second).release()); + } + + return grpc::Status::OK; + } + + void stop() + { + _stopped.store(true); + for (auto& prom : _stream_stop_promises) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } + } + +private: + void register_stream_stop_promise(std::weak_ptr> prom) + { + // If we have already stopped, set promise immediately and don't add it to list. + if (_stopped.load()) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } else { + _stream_stop_promises.push_back(prom); + } + } + + void unregister_stream_stop_promise(std::shared_ptr> prom) + { + for (auto it = _stream_stop_promises.begin(); it != _stream_stop_promises.end(); + /* ++it */) { + if (it->lock() == prom) { + it = _stream_stop_promises.erase(it); + } else { + ++it; + } + } + } + + LazyPlugin& _lazy_plugin; + + std::atomic _stopped{false}; + std::vector>> _stream_stop_promises{}; +}; + +} // namespace mavsdk_server +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk_server/src/plugins/component_metadata_server/component_metadata_server_service_impl.h b/src/mavsdk_server/src/plugins/component_metadata_server/component_metadata_server_service_impl.h new file mode 100644 index 0000000000..b00211d453 --- /dev/null +++ b/src/mavsdk_server/src/plugins/component_metadata_server/component_metadata_server_service_impl.h @@ -0,0 +1,156 @@ +// 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/component_metadata_server/component_metadata_server.proto) + +#include "component_metadata_server/component_metadata_server.grpc.pb.h" +#include "plugins/component_metadata_server/component_metadata_server.h" + +#include "mavsdk.h" + +#include "lazy_server_plugin.h" + +#include "log.h" +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace mavsdk_server { + +template< + typename ComponentMetadataServer = ComponentMetadataServer, + typename LazyServerPlugin = LazyServerPlugin> + +class ComponentMetadataServerServiceImpl final + : public rpc::component_metadata_server::ComponentMetadataServerService::Service { +public: + ComponentMetadataServerServiceImpl(LazyServerPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) {} + + static rpc::component_metadata_server::MetadataType + translateToRpcMetadataType(const mavsdk::ComponentMetadataServer::MetadataType& metadata_type) + { + switch (metadata_type) { + default: + LogErr() << "Unknown metadata_type enum value: " << static_cast(metadata_type); + // FALLTHROUGH + case mavsdk::ComponentMetadataServer::MetadataType::Parameter: + return rpc::component_metadata_server::METADATA_TYPE_PARAMETER; + case mavsdk::ComponentMetadataServer::MetadataType::Events: + return rpc::component_metadata_server::METADATA_TYPE_EVENTS; + case mavsdk::ComponentMetadataServer::MetadataType::Actuators: + return rpc::component_metadata_server::METADATA_TYPE_ACTUATORS; + } + } + + static mavsdk::ComponentMetadataServer::MetadataType + translateFromRpcMetadataType(const rpc::component_metadata_server::MetadataType metadata_type) + { + switch (metadata_type) { + default: + LogErr() << "Unknown metadata_type enum value: " << static_cast(metadata_type); + // FALLTHROUGH + case rpc::component_metadata_server::METADATA_TYPE_PARAMETER: + return mavsdk::ComponentMetadataServer::MetadataType::Parameter; + case rpc::component_metadata_server::METADATA_TYPE_EVENTS: + return mavsdk::ComponentMetadataServer::MetadataType::Events; + case rpc::component_metadata_server::METADATA_TYPE_ACTUATORS: + return mavsdk::ComponentMetadataServer::MetadataType::Actuators; + } + } + + static std::unique_ptr + translateToRpcMetadata(const mavsdk::ComponentMetadataServer::Metadata& metadata) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_type(translateToRpcMetadataType(metadata.type)); + + rpc_obj->set_json_metadata(metadata.json_metadata); + + return rpc_obj; + } + + static mavsdk::ComponentMetadataServer::Metadata + translateFromRpcMetadata(const rpc::component_metadata_server::Metadata& metadata) + { + mavsdk::ComponentMetadataServer::Metadata obj; + + obj.type = translateFromRpcMetadataType(metadata.type()); + + obj.json_metadata = metadata.json_metadata(); + + return obj; + } + + grpc::Status SetMetadata( + grpc::ServerContext* /* context */, + const rpc::component_metadata_server::SetMetadataRequest* request, + rpc::component_metadata_server::SetMetadataResponse* /* response */) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "SetMetadata sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + std::vector metadata_vec; + for (const auto& elem : request->metadata()) { + metadata_vec.push_back(translateFromRpcMetadata(elem)); + } + + _lazy_plugin.maybe_plugin()->set_metadata(metadata_vec); + + return grpc::Status::OK; + } + + void stop() + { + _stopped.store(true); + for (auto& prom : _stream_stop_promises) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } + } + +private: + void register_stream_stop_promise(std::weak_ptr> prom) + { + // If we have already stopped, set promise immediately and don't add it to list. + if (_stopped.load()) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } else { + _stream_stop_promises.push_back(prom); + } + } + + void unregister_stream_stop_promise(std::shared_ptr> prom) + { + for (auto it = _stream_stop_promises.begin(); it != _stream_stop_promises.end(); + /* ++it */) { + if (it->lock() == prom) { + it = _stream_stop_promises.erase(it); + } else { + ++it; + } + } + } + + LazyServerPlugin& _lazy_plugin; + + std::atomic _stopped{false}; + std::vector>> _stream_stop_promises{}; +}; + +} // namespace mavsdk_server +} // namespace mavsdk \ No newline at end of file From 32f1466bb942e0973fb9bd0883f5f0bfe5ef267c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 11 Apr 2024 18:03:12 +0200 Subject: [PATCH 13/15] component_information: remove old generated files --- .../component_information.grpc.pb.cc | 125 - .../component_information.grpc.pb.h | 413 --- .../component_information.pb.cc | 1811 ------------- .../component_information.pb.h | 2279 ---------------- .../component_information_server.grpc.pb.cc | 125 - .../component_information_server.grpc.pb.h | 413 --- .../component_information_server.pb.cc | 1973 -------------- .../component_information_server.pb.h | 2359 ----------------- .../component_information_service_impl.h | 272 -- ...omponent_information_server_service_impl.h | 306 --- 10 files changed, 10076 deletions(-) delete mode 100644 src/mavsdk_server/src/generated/component_information/component_information.grpc.pb.cc delete mode 100644 src/mavsdk_server/src/generated/component_information/component_information.grpc.pb.h delete mode 100644 src/mavsdk_server/src/generated/component_information/component_information.pb.cc delete mode 100644 src/mavsdk_server/src/generated/component_information/component_information.pb.h delete mode 100644 src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.cc delete mode 100644 src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.h delete mode 100644 src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.cc delete mode 100644 src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.h delete mode 100644 src/mavsdk_server/src/plugins/component_information/component_information_service_impl.h delete mode 100644 src/mavsdk_server/src/plugins/component_information_server/component_information_server_service_impl.h diff --git a/src/mavsdk_server/src/generated/component_information/component_information.grpc.pb.cc b/src/mavsdk_server/src/generated/component_information/component_information.grpc.pb.cc deleted file mode 100644 index 29d9cacd74..0000000000 --- a/src/mavsdk_server/src/generated/component_information/component_information.grpc.pb.cc +++ /dev/null @@ -1,125 +0,0 @@ -// Generated by the gRPC C++ plugin. -// If you make any local change, they will be lost. -// source: component_information/component_information.proto - -#include "component_information/component_information.pb.h" -#include "component_information/component_information.grpc.pb.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -namespace mavsdk { -namespace rpc { -namespace component_information { - -static const char* ComponentInformationService_method_names[] = { - "/mavsdk.rpc.component_information.ComponentInformationService/AccessFloatParams", - "/mavsdk.rpc.component_information.ComponentInformationService/SubscribeFloatParam", -}; - -std::unique_ptr< ComponentInformationService::Stub> ComponentInformationService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { - (void)options; - std::unique_ptr< ComponentInformationService::Stub> stub(new ComponentInformationService::Stub(channel, options)); - return stub; -} - -ComponentInformationService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) - : channel_(channel), rpcmethod_AccessFloatParams_(ComponentInformationService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeFloatParam_(ComponentInformationService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - {} - -::grpc::Status ComponentInformationService::Stub::AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::mavsdk::rpc::component_information::AccessFloatParamsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_AccessFloatParams_, context, request, response); -} - -void ComponentInformationService::Stub::async::AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::mavsdk::rpc::component_information::AccessFloatParamsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_AccessFloatParams_, context, request, response, std::move(f)); -} - -void ComponentInformationService::Stub::async::AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_AccessFloatParams_, context, request, response, reactor); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* ComponentInformationService::Stub::PrepareAsyncAccessFloatParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::component_information::AccessFloatParamsResponse, ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_AccessFloatParams_, context, request); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* ComponentInformationService::Stub::AsyncAccessFloatParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) { - auto* result = - this->PrepareAsyncAccessFloatParamsRaw(context, request, cq); - result->StartCall(); - return result; -} - -::grpc::ClientReader< ::mavsdk::rpc::component_information::FloatParamResponse>* ComponentInformationService::Stub::SubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request) { - return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::component_information::FloatParamResponse>::Create(channel_.get(), rpcmethod_SubscribeFloatParam_, context, request); -} - -void ComponentInformationService::Stub::async::SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_information::FloatParamResponse>* reactor) { - ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::component_information::FloatParamResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeFloatParam_, context, request, reactor); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information::FloatParamResponse>* ComponentInformationService::Stub::AsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::component_information::FloatParamResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeFloatParam_, context, request, true, tag); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information::FloatParamResponse>* ComponentInformationService::Stub::PrepareAsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::component_information::FloatParamResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeFloatParam_, context, request, false, nullptr); -} - -ComponentInformationService::Service::Service() { - AddMethod(new ::grpc::internal::RpcServiceMethod( - ComponentInformationService_method_names[0], - ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< ComponentInformationService::Service, ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::mavsdk::rpc::component_information::AccessFloatParamsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( - [](ComponentInformationService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* req, - ::mavsdk::rpc::component_information::AccessFloatParamsResponse* resp) { - return service->AccessFloatParams(ctx, req, resp); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - ComponentInformationService_method_names[1], - ::grpc::internal::RpcMethod::SERVER_STREAMING, - new ::grpc::internal::ServerStreamingHandler< ComponentInformationService::Service, ::mavsdk::rpc::component_information::SubscribeFloatParamRequest, ::mavsdk::rpc::component_information::FloatParamResponse>( - [](ComponentInformationService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* req, - ::grpc::ServerWriter<::mavsdk::rpc::component_information::FloatParamResponse>* writer) { - return service->SubscribeFloatParam(ctx, req, writer); - }, this))); -} - -ComponentInformationService::Service::~Service() { -} - -::grpc::Status ComponentInformationService::Service::AccessFloatParams(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response) { - (void) context; - (void) request; - (void) response; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - -::grpc::Status ComponentInformationService::Service::SubscribeFloatParam(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* writer) { - (void) context; - (void) request; - (void) writer; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - - -} // namespace mavsdk -} // namespace rpc -} // namespace component_information - diff --git a/src/mavsdk_server/src/generated/component_information/component_information.grpc.pb.h b/src/mavsdk_server/src/generated/component_information/component_information.grpc.pb.h deleted file mode 100644 index 0765b42baf..0000000000 --- a/src/mavsdk_server/src/generated/component_information/component_information.grpc.pb.h +++ /dev/null @@ -1,413 +0,0 @@ -// Generated by the gRPC C++ plugin. -// If you make any local change, they will be lost. -// source: component_information/component_information.proto -#ifndef GRPC_component_5finformation_2fcomponent_5finformation_2eproto__INCLUDED -#define GRPC_component_5finformation_2fcomponent_5finformation_2eproto__INCLUDED - -#include "component_information/component_information.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 component_information { - -// Access component information such as parameters. -class ComponentInformationService final { - public: - static constexpr char const* service_full_name() { - return "mavsdk.rpc.component_information.ComponentInformationService"; - } - class StubInterface { - public: - virtual ~StubInterface() {} - // - // List available float params. - virtual ::grpc::Status AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>> AsyncAccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>>(AsyncAccessFloatParamsRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>> PrepareAsyncAccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>>(PrepareAsyncAccessFloatParamsRaw(context, request, cq)); - } - // - // Subscribe to float param changes/updates. - std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>> SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request) { - return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>>(SubscribeFloatParamRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>> AsyncSubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>>(AsyncSubscribeFloatParamRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>> PrepareAsyncSubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>>(PrepareAsyncSubscribeFloatParamRaw(context, request, cq)); - } - class async_interface { - public: - virtual ~async_interface() {} - // - // List available float params. - virtual void AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response, std::function) = 0; - virtual void AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // - // Subscribe to float param changes/updates. - virtual void SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_information::FloatParamResponse>* reactor) = 0; - }; - typedef class async_interface experimental_async_interface; - virtual class async_interface* async() { return nullptr; } - class async_interface* experimental_async() { return async(); } - private: - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* AsyncAccessFloatParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* PrepareAsyncAccessFloatParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>* SubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>* AsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information::FloatParamResponse>* PrepareAsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) = 0; - }; - class Stub final : public StubInterface { - public: - Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); - ::grpc::Status AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>> AsyncAccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>>(AsyncAccessFloatParamsRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>> PrepareAsyncAccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>>(PrepareAsyncAccessFloatParamsRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::component_information::FloatParamResponse>> SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request) { - return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::component_information::FloatParamResponse>>(SubscribeFloatParamRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information::FloatParamResponse>> AsyncSubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information::FloatParamResponse>>(AsyncSubscribeFloatParamRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information::FloatParamResponse>> PrepareAsyncSubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information::FloatParamResponse>>(PrepareAsyncSubscribeFloatParamRaw(context, request, cq)); - } - class async final : - public StubInterface::async_interface { - public: - void AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response, std::function) override; - void AccessFloatParams(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response, ::grpc::ClientUnaryReactor* reactor) override; - void SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_information::FloatParamResponse>* reactor) override; - private: - friend class Stub; - explicit async(Stub* stub): stub_(stub) { } - Stub* stub() { return stub_; } - Stub* stub_; - }; - class async* async() override { return &async_stub_; } - - private: - std::shared_ptr< ::grpc::ChannelInterface> channel_; - class async async_stub_{this}; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* AsyncAccessFloatParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* PrepareAsyncAccessFloatParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientReader< ::mavsdk::rpc::component_information::FloatParamResponse>* SubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information::FloatParamResponse>* AsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information::FloatParamResponse>* PrepareAsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) override; - const ::grpc::internal::RpcMethod rpcmethod_AccessFloatParams_; - const ::grpc::internal::RpcMethod rpcmethod_SubscribeFloatParam_; - }; - 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(); - // - // List available float params. - virtual ::grpc::Status AccessFloatParams(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response); - // - // Subscribe to float param changes/updates. - virtual ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* writer); - }; - template - class WithAsyncMethod_AccessFloatParams : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_AccessFloatParams() { - ::grpc::Service::MarkMethodAsync(0); - } - ~WithAsyncMethod_AccessFloatParams() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status AccessFloatParams(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* /*request*/, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestAccessFloatParams(::grpc::ServerContext* context, ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithAsyncMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodAsync(1); - } - ~WithAsyncMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeFloatParam(::grpc::ServerContext* context, ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* 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); - } - }; - typedef WithAsyncMethod_AccessFloatParams > AsyncService; - template - class WithCallbackMethod_AccessFloatParams : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_AccessFloatParams() { - ::grpc::Service::MarkMethodCallback(0, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::mavsdk::rpc::component_information::AccessFloatParamsResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* request, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* response) { return this->AccessFloatParams(context, request, response); }));} - void SetMessageAllocatorFor_AccessFloatParams( - ::grpc::MessageAllocator< ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::mavsdk::rpc::component_information::AccessFloatParamsResponse>*>(handler) - ->SetMessageAllocator(allocator); - } - ~WithCallbackMethod_AccessFloatParams() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status AccessFloatParams(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* /*request*/, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* AccessFloatParams( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* /*request*/, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* /*response*/) { return nullptr; } - }; - template - class WithCallbackMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodCallback(1, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::component_information::SubscribeFloatParamRequest, ::mavsdk::rpc::component_information::FloatParamResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* request) { return this->SubscribeFloatParam(context, request); })); - } - ~WithCallbackMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::component_information::FloatParamResponse>* SubscribeFloatParam( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* /*request*/) { return nullptr; } - }; - typedef WithCallbackMethod_AccessFloatParams > CallbackService; - typedef CallbackService ExperimentalCallbackService; - template - class WithGenericMethod_AccessFloatParams : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_AccessFloatParams() { - ::grpc::Service::MarkMethodGeneric(0); - } - ~WithGenericMethod_AccessFloatParams() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status AccessFloatParams(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* /*request*/, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template - class WithGenericMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodGeneric(1); - } - ~WithGenericMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template - class WithRawMethod_AccessFloatParams : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_AccessFloatParams() { - ::grpc::Service::MarkMethodRaw(0); - } - ~WithRawMethod_AccessFloatParams() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status AccessFloatParams(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* /*request*/, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestAccessFloatParams(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodRaw(1); - } - ~WithRawMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeFloatParam(::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 WithRawCallbackMethod_AccessFloatParams : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_AccessFloatParams() { - ::grpc::Service::MarkMethodRawCallback(0, - new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->AccessFloatParams(context, request, response); })); - } - ~WithRawCallbackMethod_AccessFloatParams() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status AccessFloatParams(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* /*request*/, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* AccessFloatParams( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } - }; - template - class WithRawCallbackMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodRawCallback(1, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeFloatParam(context, request); })); - } - ~WithRawCallbackMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeFloatParam( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } - }; - template - class WithStreamedUnaryMethod_AccessFloatParams : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithStreamedUnaryMethod_AccessFloatParams() { - ::grpc::Service::MarkMethodStreamed(0, - new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::mavsdk::rpc::component_information::AccessFloatParamsResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::component_information::AccessFloatParamsRequest, ::mavsdk::rpc::component_information::AccessFloatParamsResponse>* streamer) { - return this->StreamedAccessFloatParams(context, - streamer); - })); - } - ~WithStreamedUnaryMethod_AccessFloatParams() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status AccessFloatParams(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::AccessFloatParamsRequest* /*request*/, ::mavsdk::rpc::component_information::AccessFloatParamsResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with streamed unary - virtual ::grpc::Status StreamedAccessFloatParams(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::component_information::AccessFloatParamsRequest,::mavsdk::rpc::component_information::AccessFloatParamsResponse>* server_unary_streamer) = 0; - }; - typedef WithStreamedUnaryMethod_AccessFloatParams StreamedUnaryService; - template - class WithSplitStreamingMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithSplitStreamingMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodStreamed(1, - new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::component_information::SubscribeFloatParamRequest, ::mavsdk::rpc::component_information::FloatParamResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::component_information::SubscribeFloatParamRequest, ::mavsdk::rpc::component_information::FloatParamResponse>* streamer) { - return this->StreamedSubscribeFloatParam(context, - streamer); - })); - } - ~WithSplitStreamingMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeFloatParam(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::component_information::SubscribeFloatParamRequest,::mavsdk::rpc::component_information::FloatParamResponse>* server_split_streamer) = 0; - }; - typedef WithSplitStreamingMethod_SubscribeFloatParam SplitStreamedService; - typedef WithStreamedUnaryMethod_AccessFloatParams > StreamedService; -}; - -} // namespace component_information -} // namespace rpc -} // namespace mavsdk - - -#endif // GRPC_component_5finformation_2fcomponent_5finformation_2eproto__INCLUDED diff --git a/src/mavsdk_server/src/generated/component_information/component_information.pb.cc b/src/mavsdk_server/src/generated/component_information/component_information.pb.cc deleted file mode 100644 index 0ba3d64b42..0000000000 --- a/src/mavsdk_server/src/generated/component_information/component_information.pb.cc +++ /dev/null @@ -1,1811 +0,0 @@ -// Generated by the protocol buffer compiler. DO NOT EDIT! -// source: component_information/component_information.proto - -#include "component_information/component_information.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 component_information { - template -PROTOBUF_CONSTEXPR SubscribeFloatParamRequest::SubscribeFloatParamRequest(::_pbi::ConstantInitialized) {} -struct SubscribeFloatParamRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SubscribeFloatParamRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SubscribeFloatParamRequestDefaultTypeInternal() {} - union { - SubscribeFloatParamRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeFloatParamRequestDefaultTypeInternal _SubscribeFloatParamRequest_default_instance_; - -inline constexpr FloatParamUpdate::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : name_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - value_{0}, - _cached_size_{0} {} - -template -PROTOBUF_CONSTEXPR FloatParamUpdate::FloatParamUpdate(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct FloatParamUpdateDefaultTypeInternal { - PROTOBUF_CONSTEXPR FloatParamUpdateDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~FloatParamUpdateDefaultTypeInternal() {} - union { - FloatParamUpdate _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FloatParamUpdateDefaultTypeInternal _FloatParamUpdate_default_instance_; - -inline constexpr FloatParam::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : name_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - short_description_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - long_description_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - unit_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - decimal_places_{0}, - start_value_{0}, - default_value_{0}, - min_value_{0}, - max_value_{0}, - _cached_size_{0} {} - -template -PROTOBUF_CONSTEXPR FloatParam::FloatParam(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct FloatParamDefaultTypeInternal { - PROTOBUF_CONSTEXPR FloatParamDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~FloatParamDefaultTypeInternal() {} - union { - FloatParam _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FloatParamDefaultTypeInternal _FloatParam_default_instance_; - -inline constexpr ComponentInformationResult::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : result_str_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - result_{static_cast< ::mavsdk::rpc::component_information::ComponentInformationResult_Result >(0)}, - _cached_size_{0} {} - -template -PROTOBUF_CONSTEXPR ComponentInformationResult::ComponentInformationResult(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct ComponentInformationResultDefaultTypeInternal { - PROTOBUF_CONSTEXPR ComponentInformationResultDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~ComponentInformationResultDefaultTypeInternal() {} - union { - ComponentInformationResult _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ComponentInformationResultDefaultTypeInternal _ComponentInformationResult_default_instance_; - template -PROTOBUF_CONSTEXPR AccessFloatParamsRequest::AccessFloatParamsRequest(::_pbi::ConstantInitialized) {} -struct AccessFloatParamsRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR AccessFloatParamsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~AccessFloatParamsRequestDefaultTypeInternal() {} - union { - AccessFloatParamsRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 AccessFloatParamsRequestDefaultTypeInternal _AccessFloatParamsRequest_default_instance_; - -inline constexpr FloatParamResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - param_update_{nullptr} {} - -template -PROTOBUF_CONSTEXPR FloatParamResponse::FloatParamResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct FloatParamResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR FloatParamResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~FloatParamResponseDefaultTypeInternal() {} - union { - FloatParamResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FloatParamResponseDefaultTypeInternal _FloatParamResponse_default_instance_; - -inline constexpr AccessFloatParamsResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - params_{}, - component_information_result_{nullptr} {} - -template -PROTOBUF_CONSTEXPR AccessFloatParamsResponse::AccessFloatParamsResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct AccessFloatParamsResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR AccessFloatParamsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~AccessFloatParamsResponseDefaultTypeInternal() {} - union { - AccessFloatParamsResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 AccessFloatParamsResponseDefaultTypeInternal _AccessFloatParamsResponse_default_instance_; -} // namespace component_information -} // namespace rpc -} // namespace mavsdk -static ::_pb::Metadata file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto[7]; -static const ::_pb::EnumDescriptor* file_level_enum_descriptors_component_5finformation_2fcomponent_5finformation_2eproto[1]; -static constexpr const ::_pb::ServiceDescriptor** - file_level_service_descriptors_component_5finformation_2fcomponent_5finformation_2eproto = nullptr; -const ::uint32_t TableStruct_component_5finformation_2fcomponent_5finformation_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( - protodesc_cold) = { - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _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::component_information::FloatParam, _impl_.name_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _impl_.short_description_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _impl_.long_description_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _impl_.unit_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _impl_.decimal_places_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _impl_.start_value_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _impl_.default_value_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _impl_.min_value_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParam, _impl_.max_value_), - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::AccessFloatParamsRequest, _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::component_information::AccessFloatParamsResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::AccessFloatParamsResponse, _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::component_information::AccessFloatParamsResponse, _impl_.component_information_result_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::AccessFloatParamsResponse, _impl_.params_), - 0, - ~0u, - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParamUpdate, _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::component_information::FloatParamUpdate, _impl_.name_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParamUpdate, _impl_.value_), - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::SubscribeFloatParamRequest, _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::component_information::FloatParamResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::FloatParamResponse, _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::component_information::FloatParamResponse, _impl_.param_update_), - 0, - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::ComponentInformationResult, _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::component_information::ComponentInformationResult, _impl_.result_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information::ComponentInformationResult, _impl_.result_str_), -}; - -static const ::_pbi::MigrationSchema - schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { - {0, -1, -1, sizeof(::mavsdk::rpc::component_information::FloatParam)}, - {17, -1, -1, sizeof(::mavsdk::rpc::component_information::AccessFloatParamsRequest)}, - {25, 35, -1, sizeof(::mavsdk::rpc::component_information::AccessFloatParamsResponse)}, - {37, -1, -1, sizeof(::mavsdk::rpc::component_information::FloatParamUpdate)}, - {47, -1, -1, sizeof(::mavsdk::rpc::component_information::SubscribeFloatParamRequest)}, - {55, 64, -1, sizeof(::mavsdk::rpc::component_information::FloatParamResponse)}, - {65, -1, -1, sizeof(::mavsdk::rpc::component_information::ComponentInformationResult)}, -}; - -static const ::_pb::Message* const file_default_instances[] = { - &::mavsdk::rpc::component_information::_FloatParam_default_instance_._instance, - &::mavsdk::rpc::component_information::_AccessFloatParamsRequest_default_instance_._instance, - &::mavsdk::rpc::component_information::_AccessFloatParamsResponse_default_instance_._instance, - &::mavsdk::rpc::component_information::_FloatParamUpdate_default_instance_._instance, - &::mavsdk::rpc::component_information::_SubscribeFloatParamRequest_default_instance_._instance, - &::mavsdk::rpc::component_information::_FloatParamResponse_default_instance_._instance, - &::mavsdk::rpc::component_information::_ComponentInformationResult_default_instance_._instance, -}; -const char descriptor_table_protodef_component_5finformation_2fcomponent_5finformation_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { - "\n1component_information/component_inform" - "ation.proto\022 mavsdk.rpc.component_inform" - "ation\032\024mavsdk_options.proto\"\307\001\n\nFloatPar" - "am\022\014\n\004name\030\001 \001(\t\022\031\n\021short_description\030\002 " - "\001(\t\022\030\n\020long_description\030\003 \001(\t\022\014\n\004unit\030\004 " - "\001(\t\022\026\n\016decimal_places\030\005 \001(\005\022\023\n\013start_val" - "ue\030\006 \001(\002\022\025\n\rdefault_value\030\007 \001(\002\022\021\n\tmin_v" - "alue\030\010 \001(\002\022\021\n\tmax_value\030\t \001(\002\"\032\n\030AccessF" - "loatParamsRequest\"\275\001\n\031AccessFloatParamsR" - "esponse\022b\n\034component_information_result\030" - "\001 \001(\0132<.mavsdk.rpc.component_information" - ".ComponentInformationResult\022<\n\006params\030\002 " - "\003(\0132,.mavsdk.rpc.component_information.F" - "loatParam\"/\n\020FloatParamUpdate\022\014\n\004name\030\001 " - "\001(\t\022\r\n\005value\030\002 \001(\002\"\034\n\032SubscribeFloatPara" - "mRequest\"^\n\022FloatParamResponse\022H\n\014param_" - "update\030\001 \001(\01322.mavsdk.rpc.component_info" - "rmation.FloatParamUpdate\"\315\001\n\032ComponentIn" - "formationResult\022S\n\006result\030\001 \001(\0162C.mavsdk" - ".rpc.component_information.ComponentInfo" - "rmationResult.Result\022\022\n\nresult_str\030\002 \001(\t" - "\"F\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT" - "_SUCCESS\020\001\022\024\n\020RESULT_NO_SYSTEM\020\0032\306\002\n\033Com" - "ponentInformationService\022\222\001\n\021AccessFloat" - "Params\022:.mavsdk.rpc.component_informatio" - "n.AccessFloatParamsRequest\032;.mavsdk.rpc." - "component_information.AccessFloatParamsR" - "esponse\"\004\200\265\030\001\022\221\001\n\023SubscribeFloatParam\022<." - "mavsdk.rpc.component_information.Subscri" - "beFloatParamRequest\0324.mavsdk.rpc.compone" - "nt_information.FloatParamResponse\"\004\200\265\030\0000" - "\001B<\n\037io.mavsdk.component_informationB\031Co" - "mponentInformationProtob\006proto3" -}; -static const ::_pbi::DescriptorTable* const descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_deps[1] = - { - &::descriptor_table_mavsdk_5foptions_2eproto, -}; -static ::absl::once_flag descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once; -const ::_pbi::DescriptorTable descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto = { - false, - false, - 1311, - descriptor_table_protodef_component_5finformation_2fcomponent_5finformation_2eproto, - "component_information/component_information.proto", - &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once, - descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_deps, - 1, - 7, - schemas, - file_default_instances, - TableStruct_component_5finformation_2fcomponent_5finformation_2eproto::offsets, - file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto, - file_level_enum_descriptors_component_5finformation_2fcomponent_5finformation_2eproto, - file_level_service_descriptors_component_5finformation_2fcomponent_5finformation_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_component_5finformation_2fcomponent_5finformation_2eproto_getter() { - return &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto; -} -// Force running AddDescriptors() at dynamic initialization time. -PROTOBUF_ATTRIBUTE_INIT_PRIORITY2 -static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_component_5finformation_2fcomponent_5finformation_2eproto(&descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto); -namespace mavsdk { -namespace rpc { -namespace component_information { -const ::google::protobuf::EnumDescriptor* ComponentInformationResult_Result_descriptor() { - ::google::protobuf::internal::AssignDescriptors(&descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto); - return file_level_enum_descriptors_component_5finformation_2fcomponent_5finformation_2eproto[0]; -} -PROTOBUF_CONSTINIT const uint32_t ComponentInformationResult_Result_internal_data_[] = { - 131072u, 32u, 2u, }; -bool ComponentInformationResult_Result_IsValid(int value) { - return 0 <= value && value <= 3 && ((11u >> value) & 1) != 0; -} -#if (__cplusplus < 201703) && \ - (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) - -constexpr ComponentInformationResult_Result ComponentInformationResult::RESULT_UNKNOWN; -constexpr ComponentInformationResult_Result ComponentInformationResult::RESULT_SUCCESS; -constexpr ComponentInformationResult_Result ComponentInformationResult::RESULT_NO_SYSTEM; -constexpr ComponentInformationResult_Result ComponentInformationResult::Result_MIN; -constexpr ComponentInformationResult_Result ComponentInformationResult::Result_MAX; -constexpr int ComponentInformationResult::Result_ARRAYSIZE; - -#endif // (__cplusplus < 201703) && - // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) -// =================================================================== - -class FloatParam::_Internal { - public: -}; - -FloatParam::FloatParam(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information.FloatParam) -} -inline PROTOBUF_NDEBUG_INLINE FloatParam::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : name_(arena, from.name_), - short_description_(arena, from.short_description_), - long_description_(arena, from.long_description_), - unit_(arena, from.unit_), - _cached_size_{0} {} - -FloatParam::FloatParam( - ::google::protobuf::Arena* arena, - const FloatParam& from) - : ::google::protobuf::Message(arena) { - FloatParam* 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_, decimal_places_), - reinterpret_cast(&from._impl_) + - offsetof(Impl_, decimal_places_), - offsetof(Impl_, max_value_) - - offsetof(Impl_, decimal_places_) + - sizeof(Impl_::max_value_)); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information.FloatParam) -} -inline PROTOBUF_NDEBUG_INLINE FloatParam::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : name_(arena), - short_description_(arena), - long_description_(arena), - unit_(arena), - _cached_size_{0} {} - -inline void FloatParam::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, decimal_places_), - 0, - offsetof(Impl_, max_value_) - - offsetof(Impl_, decimal_places_) + - sizeof(Impl_::max_value_)); -} -FloatParam::~FloatParam() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information.FloatParam) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void FloatParam::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.name_.Destroy(); - _impl_.short_description_.Destroy(); - _impl_.long_description_.Destroy(); - _impl_.unit_.Destroy(); - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void FloatParam::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information.FloatParam) - 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_.short_description_.ClearToEmpty(); - _impl_.long_description_.ClearToEmpty(); - _impl_.unit_.ClearToEmpty(); - ::memset(&_impl_.decimal_places_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.max_value_) - - reinterpret_cast(&_impl_.decimal_places_)) + sizeof(_impl_.max_value_)); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* FloatParam::_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<4, 9, 0, 101, 2> FloatParam::_table_ = { - { - 0, // no _has_bits_ - 0, // no _extensions_ - 9, 120, // max_field_number, fast_idx_mask - offsetof(decltype(_table_), field_lookup_table), - 4294966784, // skipmap - offsetof(decltype(_table_), field_entries), - 9, // num_field_entries - 0, // num_aux_entries - offsetof(decltype(_table_), field_names), // no aux_entries - &_FloatParam_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - {::_pbi::TcParser::MiniParse, {}}, - // string name = 1; - {::_pbi::TcParser::FastUS1, - {10, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.name_)}}, - // string short_description = 2; - {::_pbi::TcParser::FastUS1, - {18, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.short_description_)}}, - // string long_description = 3; - {::_pbi::TcParser::FastUS1, - {26, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.long_description_)}}, - // string unit = 4; - {::_pbi::TcParser::FastUS1, - {34, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.unit_)}}, - // int32 decimal_places = 5; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FloatParam, _impl_.decimal_places_), 63>(), - {40, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.decimal_places_)}}, - // float start_value = 6; - {::_pbi::TcParser::FastF32S1, - {53, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.start_value_)}}, - // float default_value = 7; - {::_pbi::TcParser::FastF32S1, - {61, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.default_value_)}}, - // float min_value = 8; - {::_pbi::TcParser::FastF32S1, - {69, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.min_value_)}}, - // float max_value = 9; - {::_pbi::TcParser::FastF32S1, - {77, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.max_value_)}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - }}, {{ - 65535, 65535 - }}, {{ - // string name = 1; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.name_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // string short_description = 2; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.short_description_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // string long_description = 3; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.long_description_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // string unit = 4; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.unit_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // int32 decimal_places = 5; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.decimal_places_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, - // float start_value = 6; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.start_value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float default_value = 7; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.default_value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float min_value = 8; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.min_value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float max_value = 9; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.max_value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - }}, - // no aux_entries - {{ - "\53\4\21\20\4\0\0\0\0\0\0\0\0\0\0\0" - "mavsdk.rpc.component_information.FloatParam" - "name" - "short_description" - "long_description" - "unit" - }}, -}; - -::uint8_t* FloatParam::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information.FloatParam) - ::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.component_information.FloatParam.name"); - target = stream->WriteStringMaybeAliased(1, _s, target); - } - - // string short_description = 2; - if (!this->_internal_short_description().empty()) { - const std::string& _s = this->_internal_short_description(); - ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_information.FloatParam.short_description"); - target = stream->WriteStringMaybeAliased(2, _s, target); - } - - // string long_description = 3; - if (!this->_internal_long_description().empty()) { - const std::string& _s = this->_internal_long_description(); - ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_information.FloatParam.long_description"); - target = stream->WriteStringMaybeAliased(3, _s, target); - } - - // string unit = 4; - if (!this->_internal_unit().empty()) { - const std::string& _s = this->_internal_unit(); - ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_information.FloatParam.unit"); - target = stream->WriteStringMaybeAliased(4, _s, target); - } - - // int32 decimal_places = 5; - if (this->_internal_decimal_places() != 0) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteInt32ToArrayWithField<5>( - stream, this->_internal_decimal_places(), target); - } - - // float start_value = 6; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_start_value = this->_internal_start_value(); - ::uint32_t raw_start_value; - memcpy(&raw_start_value, &tmp_start_value, sizeof(tmp_start_value)); - if (raw_start_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 6, this->_internal_start_value(), target); - } - - // float default_value = 7; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_default_value = this->_internal_default_value(); - ::uint32_t raw_default_value; - memcpy(&raw_default_value, &tmp_default_value, sizeof(tmp_default_value)); - if (raw_default_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 7, this->_internal_default_value(), target); - } - - // float min_value = 8; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_min_value = this->_internal_min_value(); - ::uint32_t raw_min_value; - memcpy(&raw_min_value, &tmp_min_value, sizeof(tmp_min_value)); - if (raw_min_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 8, this->_internal_min_value(), target); - } - - // float max_value = 9; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_max_value = this->_internal_max_value(); - ::uint32_t raw_max_value; - memcpy(&raw_max_value, &tmp_max_value, sizeof(tmp_max_value)); - if (raw_max_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 9, this->_internal_max_value(), 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.component_information.FloatParam) - return target; -} - -::size_t FloatParam::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information.FloatParam) - ::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 short_description = 2; - if (!this->_internal_short_description().empty()) { - total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( - this->_internal_short_description()); - } - - // string long_description = 3; - if (!this->_internal_long_description().empty()) { - total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( - this->_internal_long_description()); - } - - // string unit = 4; - if (!this->_internal_unit().empty()) { - total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( - this->_internal_unit()); - } - - // int32 decimal_places = 5; - if (this->_internal_decimal_places() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_decimal_places()); - } - - // float start_value = 6; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_start_value = this->_internal_start_value(); - ::uint32_t raw_start_value; - memcpy(&raw_start_value, &tmp_start_value, sizeof(tmp_start_value)); - if (raw_start_value != 0) { - total_size += 5; - } - - // float default_value = 7; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_default_value = this->_internal_default_value(); - ::uint32_t raw_default_value; - memcpy(&raw_default_value, &tmp_default_value, sizeof(tmp_default_value)); - if (raw_default_value != 0) { - total_size += 5; - } - - // float min_value = 8; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_min_value = this->_internal_min_value(); - ::uint32_t raw_min_value; - memcpy(&raw_min_value, &tmp_min_value, sizeof(tmp_min_value)); - if (raw_min_value != 0) { - total_size += 5; - } - - // float max_value = 9; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_max_value = this->_internal_max_value(); - ::uint32_t raw_max_value; - memcpy(&raw_max_value, &tmp_max_value, sizeof(tmp_max_value)); - if (raw_max_value != 0) { - total_size += 5; - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData FloatParam::_class_data_ = { - FloatParam::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* FloatParam::GetClassData() const { - return &_class_data_; -} - -void FloatParam::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.component_information.FloatParam) - 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_short_description().empty()) { - _this->_internal_set_short_description(from._internal_short_description()); - } - if (!from._internal_long_description().empty()) { - _this->_internal_set_long_description(from._internal_long_description()); - } - if (!from._internal_unit().empty()) { - _this->_internal_set_unit(from._internal_unit()); - } - if (from._internal_decimal_places() != 0) { - _this->_internal_set_decimal_places(from._internal_decimal_places()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_start_value = from._internal_start_value(); - ::uint32_t raw_start_value; - memcpy(&raw_start_value, &tmp_start_value, sizeof(tmp_start_value)); - if (raw_start_value != 0) { - _this->_internal_set_start_value(from._internal_start_value()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_default_value = from._internal_default_value(); - ::uint32_t raw_default_value; - memcpy(&raw_default_value, &tmp_default_value, sizeof(tmp_default_value)); - if (raw_default_value != 0) { - _this->_internal_set_default_value(from._internal_default_value()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_min_value = from._internal_min_value(); - ::uint32_t raw_min_value; - memcpy(&raw_min_value, &tmp_min_value, sizeof(tmp_min_value)); - if (raw_min_value != 0) { - _this->_internal_set_min_value(from._internal_min_value()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_max_value = from._internal_max_value(); - ::uint32_t raw_max_value; - memcpy(&raw_max_value, &tmp_max_value, sizeof(tmp_max_value)); - if (raw_max_value != 0) { - _this->_internal_set_max_value(from._internal_max_value()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void FloatParam::CopyFrom(const FloatParam& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information.FloatParam) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool FloatParam::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* FloatParam::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void FloatParam::InternalSwap(FloatParam* 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_.short_description_, &other->_impl_.short_description_, arena); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.long_description_, &other->_impl_.long_description_, arena); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.unit_, &other->_impl_.unit_, arena); - ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.max_value_) - + sizeof(FloatParam::_impl_.max_value_) - - PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.decimal_places_)>( - reinterpret_cast(&_impl_.decimal_places_), - reinterpret_cast(&other->_impl_.decimal_places_)); -} - -::google::protobuf::Metadata FloatParam::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_getter, &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once, - file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto[0]); -} -// =================================================================== - -class AccessFloatParamsRequest::_Internal { - public: -}; - -AccessFloatParamsRequest::AccessFloatParamsRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information.AccessFloatParamsRequest) -} -AccessFloatParamsRequest::AccessFloatParamsRequest( - ::google::protobuf::Arena* arena, - const AccessFloatParamsRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - AccessFloatParamsRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information.AccessFloatParamsRequest) -} - - - - - - - - - -::google::protobuf::Metadata AccessFloatParamsRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_getter, &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once, - file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto[1]); -} -// =================================================================== - -class AccessFloatParamsResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(AccessFloatParamsResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::component_information::ComponentInformationResult& component_information_result(const AccessFloatParamsResponse* msg); - static void set_has_component_information_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::component_information::ComponentInformationResult& AccessFloatParamsResponse::_Internal::component_information_result(const AccessFloatParamsResponse* msg) { - return *msg->_impl_.component_information_result_; -} -AccessFloatParamsResponse::AccessFloatParamsResponse(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information.AccessFloatParamsResponse) -} -inline PROTOBUF_NDEBUG_INLINE AccessFloatParamsResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0}, - params_{visibility, arena, from.params_} {} - -AccessFloatParamsResponse::AccessFloatParamsResponse( - ::google::protobuf::Arena* arena, - const AccessFloatParamsResponse& from) - : ::google::protobuf::Message(arena) { - AccessFloatParamsResponse* 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_.component_information_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::component_information::ComponentInformationResult>(arena, *from._impl_.component_information_result_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information.AccessFloatParamsResponse) -} -inline PROTOBUF_NDEBUG_INLINE AccessFloatParamsResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0}, - params_{visibility, arena} {} - -inline void AccessFloatParamsResponse::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.component_information_result_ = {}; -} -AccessFloatParamsResponse::~AccessFloatParamsResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information.AccessFloatParamsResponse) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void AccessFloatParamsResponse::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.component_information_result_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void AccessFloatParamsResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information.AccessFloatParamsResponse) - 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_.params_.Clear(); - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.component_information_result_ != nullptr); - _impl_.component_information_result_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* AccessFloatParamsResponse::_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> AccessFloatParamsResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(AccessFloatParamsResponse, _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), - &_AccessFloatParamsResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // repeated .mavsdk.rpc.component_information.FloatParam params = 2; - {::_pbi::TcParser::FastMtR1, - {18, 63, 1, PROTOBUF_FIELD_OFFSET(AccessFloatParamsResponse, _impl_.params_)}}, - // .mavsdk.rpc.component_information.ComponentInformationResult component_information_result = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(AccessFloatParamsResponse, _impl_.component_information_result_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.component_information.ComponentInformationResult component_information_result = 1; - {PROTOBUF_FIELD_OFFSET(AccessFloatParamsResponse, _impl_.component_information_result_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // repeated .mavsdk.rpc.component_information.FloatParam params = 2; - {PROTOBUF_FIELD_OFFSET(AccessFloatParamsResponse, _impl_.params_), -1, 1, - (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_information::ComponentInformationResult>()}, - {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_information::FloatParam>()}, - }}, {{ - }}, -}; - -::uint8_t* AccessFloatParamsResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information.AccessFloatParamsResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.component_information.ComponentInformationResult component_information_result = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::component_information_result(this), - _Internal::component_information_result(this).GetCachedSize(), target, stream); - } - - // repeated .mavsdk.rpc.component_information.FloatParam params = 2; - for (unsigned i = 0, - n = static_cast(this->_internal_params_size()); i < n; i++) { - const auto& repfield = this->_internal_params().Get(i); - target = ::google::protobuf::internal::WireFormatLite:: - InternalWriteMessage(2, 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.component_information.AccessFloatParamsResponse) - return target; -} - -::size_t AccessFloatParamsResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information.AccessFloatParamsResponse) - ::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.component_information.FloatParam params = 2; - total_size += 1UL * this->_internal_params_size(); - for (const auto& msg : this->_internal_params()) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSize(msg); - } - // .mavsdk.rpc.component_information.ComponentInformationResult component_information_result = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.component_information_result_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData AccessFloatParamsResponse::_class_data_ = { - AccessFloatParamsResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* AccessFloatParamsResponse::GetClassData() const { - return &_class_data_; -} - -void AccessFloatParamsResponse::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.component_information.AccessFloatParamsResponse) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - _this->_internal_mutable_params()->MergeFrom( - from._internal_params()); - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_component_information_result()->::mavsdk::rpc::component_information::ComponentInformationResult::MergeFrom( - from._internal_component_information_result()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void AccessFloatParamsResponse::CopyFrom(const AccessFloatParamsResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information.AccessFloatParamsResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool AccessFloatParamsResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* AccessFloatParamsResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void AccessFloatParamsResponse::InternalSwap(AccessFloatParamsResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - _impl_.params_.InternalSwap(&other->_impl_.params_); - swap(_impl_.component_information_result_, other->_impl_.component_information_result_); -} - -::google::protobuf::Metadata AccessFloatParamsResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_getter, &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once, - file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto[2]); -} -// =================================================================== - -class FloatParamUpdate::_Internal { - public: -}; - -FloatParamUpdate::FloatParamUpdate(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information.FloatParamUpdate) -} -inline PROTOBUF_NDEBUG_INLINE FloatParamUpdate::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : name_(arena, from.name_), - _cached_size_{0} {} - -FloatParamUpdate::FloatParamUpdate( - ::google::protobuf::Arena* arena, - const FloatParamUpdate& from) - : ::google::protobuf::Message(arena) { - FloatParamUpdate* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - _impl_.value_ = from._impl_.value_; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information.FloatParamUpdate) -} -inline PROTOBUF_NDEBUG_INLINE FloatParamUpdate::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : name_(arena), - _cached_size_{0} {} - -inline void FloatParamUpdate::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.value_ = {}; -} -FloatParamUpdate::~FloatParamUpdate() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information.FloatParamUpdate) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void FloatParamUpdate::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.name_.Destroy(); - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void FloatParamUpdate::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information.FloatParamUpdate) - 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_.value_ = 0; - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* FloatParamUpdate::_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, 62, 2> FloatParamUpdate::_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 - &_FloatParamUpdate_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // float value = 2; - {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParamUpdate, _impl_.value_)}}, - // string name = 1; - {::_pbi::TcParser::FastUS1, - {10, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParamUpdate, _impl_.name_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // string name = 1; - {PROTOBUF_FIELD_OFFSET(FloatParamUpdate, _impl_.name_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // float value = 2; - {PROTOBUF_FIELD_OFFSET(FloatParamUpdate, _impl_.value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - }}, - // no aux_entries - {{ - "\61\4\0\0\0\0\0\0" - "mavsdk.rpc.component_information.FloatParamUpdate" - "name" - }}, -}; - -::uint8_t* FloatParamUpdate::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information.FloatParamUpdate) - ::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.component_information.FloatParamUpdate.name"); - target = stream->WriteStringMaybeAliased(1, _s, target); - } - - // float value = 2; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_value = this->_internal_value(); - ::uint32_t raw_value; - memcpy(&raw_value, &tmp_value, sizeof(tmp_value)); - if (raw_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_value(), 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.component_information.FloatParamUpdate) - return target; -} - -::size_t FloatParamUpdate::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information.FloatParamUpdate) - ::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()); - } - - // float value = 2; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_value = this->_internal_value(); - ::uint32_t raw_value; - memcpy(&raw_value, &tmp_value, sizeof(tmp_value)); - if (raw_value != 0) { - total_size += 5; - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData FloatParamUpdate::_class_data_ = { - FloatParamUpdate::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* FloatParamUpdate::GetClassData() const { - return &_class_data_; -} - -void FloatParamUpdate::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.component_information.FloatParamUpdate) - 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()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_value = from._internal_value(); - ::uint32_t raw_value; - memcpy(&raw_value, &tmp_value, sizeof(tmp_value)); - if (raw_value != 0) { - _this->_internal_set_value(from._internal_value()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void FloatParamUpdate::CopyFrom(const FloatParamUpdate& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information.FloatParamUpdate) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool FloatParamUpdate::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* FloatParamUpdate::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void FloatParamUpdate::InternalSwap(FloatParamUpdate* 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); - swap(_impl_.value_, other->_impl_.value_); -} - -::google::protobuf::Metadata FloatParamUpdate::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_getter, &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once, - file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto[3]); -} -// =================================================================== - -class SubscribeFloatParamRequest::_Internal { - public: -}; - -SubscribeFloatParamRequest::SubscribeFloatParamRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information.SubscribeFloatParamRequest) -} -SubscribeFloatParamRequest::SubscribeFloatParamRequest( - ::google::protobuf::Arena* arena, - const SubscribeFloatParamRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeFloatParamRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information.SubscribeFloatParamRequest) -} - - - - - - - - - -::google::protobuf::Metadata SubscribeFloatParamRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_getter, &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once, - file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto[4]); -} -// =================================================================== - -class FloatParamResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(FloatParamResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::component_information::FloatParamUpdate& param_update(const FloatParamResponse* msg); - static void set_has_param_update(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::component_information::FloatParamUpdate& FloatParamResponse::_Internal::param_update(const FloatParamResponse* msg) { - return *msg->_impl_.param_update_; -} -FloatParamResponse::FloatParamResponse(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information.FloatParamResponse) -} -inline PROTOBUF_NDEBUG_INLINE FloatParamResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -FloatParamResponse::FloatParamResponse( - ::google::protobuf::Arena* arena, - const FloatParamResponse& from) - : ::google::protobuf::Message(arena) { - FloatParamResponse* 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_.param_update_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::component_information::FloatParamUpdate>(arena, *from._impl_.param_update_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information.FloatParamResponse) -} -inline PROTOBUF_NDEBUG_INLINE FloatParamResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void FloatParamResponse::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.param_update_ = {}; -} -FloatParamResponse::~FloatParamResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information.FloatParamResponse) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void FloatParamResponse::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.param_update_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void FloatParamResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information.FloatParamResponse) - 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_.param_update_ != nullptr); - _impl_.param_update_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* FloatParamResponse::_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> FloatParamResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(FloatParamResponse, _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), - &_FloatParamResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.component_information.FloatParamUpdate param_update = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(FloatParamResponse, _impl_.param_update_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.component_information.FloatParamUpdate param_update = 1; - {PROTOBUF_FIELD_OFFSET(FloatParamResponse, _impl_.param_update_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_information::FloatParamUpdate>()}, - }}, {{ - }}, -}; - -::uint8_t* FloatParamResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information.FloatParamResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.component_information.FloatParamUpdate param_update = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::param_update(this), - _Internal::param_update(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.component_information.FloatParamResponse) - return target; -} - -::size_t FloatParamResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information.FloatParamResponse) - ::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.component_information.FloatParamUpdate param_update = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.param_update_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData FloatParamResponse::_class_data_ = { - FloatParamResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* FloatParamResponse::GetClassData() const { - return &_class_data_; -} - -void FloatParamResponse::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.component_information.FloatParamResponse) - 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_param_update()->::mavsdk::rpc::component_information::FloatParamUpdate::MergeFrom( - from._internal_param_update()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void FloatParamResponse::CopyFrom(const FloatParamResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information.FloatParamResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool FloatParamResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* FloatParamResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void FloatParamResponse::InternalSwap(FloatParamResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.param_update_, other->_impl_.param_update_); -} - -::google::protobuf::Metadata FloatParamResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_getter, &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once, - file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto[5]); -} -// =================================================================== - -class ComponentInformationResult::_Internal { - public: -}; - -ComponentInformationResult::ComponentInformationResult(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information.ComponentInformationResult) -} -inline PROTOBUF_NDEBUG_INLINE ComponentInformationResult::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : result_str_(arena, from.result_str_), - _cached_size_{0} {} - -ComponentInformationResult::ComponentInformationResult( - ::google::protobuf::Arena* arena, - const ComponentInformationResult& from) - : ::google::protobuf::Message(arena) { - ComponentInformationResult* 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.component_information.ComponentInformationResult) -} -inline PROTOBUF_NDEBUG_INLINE ComponentInformationResult::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : result_str_(arena), - _cached_size_{0} {} - -inline void ComponentInformationResult::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.result_ = {}; -} -ComponentInformationResult::~ComponentInformationResult() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information.ComponentInformationResult) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void ComponentInformationResult::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.result_str_.Destroy(); - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void ComponentInformationResult::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information.ComponentInformationResult) - 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* ComponentInformationResult::_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, 78, 2> ComponentInformationResult::_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 - &_ComponentInformationResult_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // string result_str = 2; - {::_pbi::TcParser::FastUS1, - {18, 63, 0, PROTOBUF_FIELD_OFFSET(ComponentInformationResult, _impl_.result_str_)}}, - // .mavsdk.rpc.component_information.ComponentInformationResult.Result result = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ComponentInformationResult, _impl_.result_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(ComponentInformationResult, _impl_.result_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.component_information.ComponentInformationResult.Result result = 1; - {PROTOBUF_FIELD_OFFSET(ComponentInformationResult, _impl_.result_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - // string result_str = 2; - {PROTOBUF_FIELD_OFFSET(ComponentInformationResult, _impl_.result_str_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - }}, - // no aux_entries - {{ - "\73\0\12\0\0\0\0\0" - "mavsdk.rpc.component_information.ComponentInformationResult" - "result_str" - }}, -}; - -::uint8_t* ComponentInformationResult::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information.ComponentInformationResult) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - // .mavsdk.rpc.component_information.ComponentInformationResult.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.component_information.ComponentInformationResult.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.component_information.ComponentInformationResult) - return target; -} - -::size_t ComponentInformationResult::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information.ComponentInformationResult) - ::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.component_information.ComponentInformationResult.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 ComponentInformationResult::_class_data_ = { - ComponentInformationResult::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* ComponentInformationResult::GetClassData() const { - return &_class_data_; -} - -void ComponentInformationResult::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.component_information.ComponentInformationResult) - 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 ComponentInformationResult::CopyFrom(const ComponentInformationResult& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information.ComponentInformationResult) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool ComponentInformationResult::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* ComponentInformationResult::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void ComponentInformationResult::InternalSwap(ComponentInformationResult* 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 ComponentInformationResult::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_getter, &descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto_once, - file_level_metadata_component_5finformation_2fcomponent_5finformation_2eproto[6]); -} -// @@protoc_insertion_point(namespace_scope) -} // namespace component_information -} // 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/component_information/component_information.pb.h b/src/mavsdk_server/src/generated/component_information/component_information.pb.h deleted file mode 100644 index 0666251081..0000000000 --- a/src/mavsdk_server/src/generated/component_information/component_information.pb.h +++ /dev/null @@ -1,2279 +0,0 @@ -// Generated by the protocol buffer compiler. DO NOT EDIT! -// source: component_information/component_information.proto -// Protobuf C++ Version: 4.25.1 - -#ifndef GOOGLE_PROTOBUF_INCLUDED_component_5finformation_2fcomponent_5finformation_2eproto_2epb_2eh -#define GOOGLE_PROTOBUF_INCLUDED_component_5finformation_2fcomponent_5finformation_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_component_5finformation_2fcomponent_5finformation_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_component_5finformation_2fcomponent_5finformation_2eproto { - static const ::uint32_t offsets[]; -}; -extern const ::google::protobuf::internal::DescriptorTable - descriptor_table_component_5finformation_2fcomponent_5finformation_2eproto; -namespace mavsdk { -namespace rpc { -namespace component_information { -class AccessFloatParamsRequest; -struct AccessFloatParamsRequestDefaultTypeInternal; -extern AccessFloatParamsRequestDefaultTypeInternal _AccessFloatParamsRequest_default_instance_; -class AccessFloatParamsResponse; -struct AccessFloatParamsResponseDefaultTypeInternal; -extern AccessFloatParamsResponseDefaultTypeInternal _AccessFloatParamsResponse_default_instance_; -class ComponentInformationResult; -struct ComponentInformationResultDefaultTypeInternal; -extern ComponentInformationResultDefaultTypeInternal _ComponentInformationResult_default_instance_; -class FloatParam; -struct FloatParamDefaultTypeInternal; -extern FloatParamDefaultTypeInternal _FloatParam_default_instance_; -class FloatParamResponse; -struct FloatParamResponseDefaultTypeInternal; -extern FloatParamResponseDefaultTypeInternal _FloatParamResponse_default_instance_; -class FloatParamUpdate; -struct FloatParamUpdateDefaultTypeInternal; -extern FloatParamUpdateDefaultTypeInternal _FloatParamUpdate_default_instance_; -class SubscribeFloatParamRequest; -struct SubscribeFloatParamRequestDefaultTypeInternal; -extern SubscribeFloatParamRequestDefaultTypeInternal _SubscribeFloatParamRequest_default_instance_; -} // namespace component_information -} // namespace rpc -} // namespace mavsdk -namespace google { -namespace protobuf { -} // namespace protobuf -} // namespace google - -namespace mavsdk { -namespace rpc { -namespace component_information { -enum ComponentInformationResult_Result : int { - ComponentInformationResult_Result_RESULT_UNKNOWN = 0, - ComponentInformationResult_Result_RESULT_SUCCESS = 1, - ComponentInformationResult_Result_RESULT_NO_SYSTEM = 3, - ComponentInformationResult_Result_ComponentInformationResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = - std::numeric_limits<::int32_t>::min(), - ComponentInformationResult_Result_ComponentInformationResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = - std::numeric_limits<::int32_t>::max(), -}; - -bool ComponentInformationResult_Result_IsValid(int value); -extern const uint32_t ComponentInformationResult_Result_internal_data_[]; -constexpr ComponentInformationResult_Result ComponentInformationResult_Result_Result_MIN = static_cast(0); -constexpr ComponentInformationResult_Result ComponentInformationResult_Result_Result_MAX = static_cast(3); -constexpr int ComponentInformationResult_Result_Result_ARRAYSIZE = 3 + 1; -const ::google::protobuf::EnumDescriptor* -ComponentInformationResult_Result_descriptor(); -template -const std::string& ComponentInformationResult_Result_Name(T value) { - static_assert(std::is_same::value || - std::is_integral::value, - "Incorrect type passed to Result_Name()."); - return ComponentInformationResult_Result_Name(static_cast(value)); -} -template <> -inline const std::string& ComponentInformationResult_Result_Name(ComponentInformationResult_Result value) { - return ::google::protobuf::internal::NameOfDenseEnum( - static_cast(value)); -} -inline bool ComponentInformationResult_Result_Parse(absl::string_view name, ComponentInformationResult_Result* value) { - return ::google::protobuf::internal::ParseNamedEnum( - ComponentInformationResult_Result_descriptor(), name, value); -} - -// =================================================================== - - -// ------------------------------------------------------------------- - -class SubscribeFloatParamRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information.SubscribeFloatParamRequest) */ { - public: - inline SubscribeFloatParamRequest() : SubscribeFloatParamRequest(nullptr) {} - template - explicit PROTOBUF_CONSTEXPR SubscribeFloatParamRequest(::google::protobuf::internal::ConstantInitialized); - - inline SubscribeFloatParamRequest(const SubscribeFloatParamRequest& from) - : SubscribeFloatParamRequest(nullptr, from) {} - SubscribeFloatParamRequest(SubscribeFloatParamRequest&& from) noexcept - : SubscribeFloatParamRequest() { - *this = ::std::move(from); - } - - inline SubscribeFloatParamRequest& operator=(const SubscribeFloatParamRequest& from) { - CopyFrom(from); - return *this; - } - inline SubscribeFloatParamRequest& operator=(SubscribeFloatParamRequest&& 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 SubscribeFloatParamRequest& default_instance() { - return *internal_default_instance(); - } - static inline const SubscribeFloatParamRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeFloatParamRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 4; - - friend void swap(SubscribeFloatParamRequest& a, SubscribeFloatParamRequest& b) { - a.Swap(&b); - } - inline void Swap(SubscribeFloatParamRequest* 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(SubscribeFloatParamRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - SubscribeFloatParamRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeFloatParamRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeFloatParamRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); - } - public: - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information.SubscribeFloatParamRequest"; - } - protected: - explicit SubscribeFloatParamRequest(::google::protobuf::Arena* arena); - SubscribeFloatParamRequest(::google::protobuf::Arena* arena, const SubscribeFloatParamRequest& from); - public: - - ::google::protobuf::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.SubscribeFloatParamRequest) - 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_component_5finformation_2fcomponent_5finformation_2eproto; -};// ------------------------------------------------------------------- - -class FloatParamUpdate final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information.FloatParamUpdate) */ { - public: - inline FloatParamUpdate() : FloatParamUpdate(nullptr) {} - ~FloatParamUpdate() override; - template - explicit PROTOBUF_CONSTEXPR FloatParamUpdate(::google::protobuf::internal::ConstantInitialized); - - inline FloatParamUpdate(const FloatParamUpdate& from) - : FloatParamUpdate(nullptr, from) {} - FloatParamUpdate(FloatParamUpdate&& from) noexcept - : FloatParamUpdate() { - *this = ::std::move(from); - } - - inline FloatParamUpdate& operator=(const FloatParamUpdate& from) { - CopyFrom(from); - return *this; - } - inline FloatParamUpdate& operator=(FloatParamUpdate&& 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 FloatParamUpdate& default_instance() { - return *internal_default_instance(); - } - static inline const FloatParamUpdate* internal_default_instance() { - return reinterpret_cast( - &_FloatParamUpdate_default_instance_); - } - static constexpr int kIndexInFileMessages = - 3; - - friend void swap(FloatParamUpdate& a, FloatParamUpdate& b) { - a.Swap(&b); - } - inline void Swap(FloatParamUpdate* 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(FloatParamUpdate* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - FloatParamUpdate* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FloatParamUpdate& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FloatParamUpdate& from) { - FloatParamUpdate::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(FloatParamUpdate* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information.FloatParamUpdate"; - } - protected: - explicit FloatParamUpdate(::google::protobuf::Arena* arena); - FloatParamUpdate(::google::protobuf::Arena* arena, const FloatParamUpdate& 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, - kValueFieldNumber = 2, - }; - // 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: - // float value = 2; - void clear_value() ; - float value() const; - void set_value(float value); - - private: - float _internal_value() const; - void _internal_set_value(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParamUpdate) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, - 62, 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_; - float value_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_2fcomponent_5finformation_2eproto; -};// ------------------------------------------------------------------- - -class FloatParam final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information.FloatParam) */ { - public: - inline FloatParam() : FloatParam(nullptr) {} - ~FloatParam() override; - template - explicit PROTOBUF_CONSTEXPR FloatParam(::google::protobuf::internal::ConstantInitialized); - - inline FloatParam(const FloatParam& from) - : FloatParam(nullptr, from) {} - FloatParam(FloatParam&& from) noexcept - : FloatParam() { - *this = ::std::move(from); - } - - inline FloatParam& operator=(const FloatParam& from) { - CopyFrom(from); - return *this; - } - inline FloatParam& operator=(FloatParam&& 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 FloatParam& default_instance() { - return *internal_default_instance(); - } - static inline const FloatParam* internal_default_instance() { - return reinterpret_cast( - &_FloatParam_default_instance_); - } - static constexpr int kIndexInFileMessages = - 0; - - friend void swap(FloatParam& a, FloatParam& b) { - a.Swap(&b); - } - inline void Swap(FloatParam* 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(FloatParam* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - FloatParam* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FloatParam& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FloatParam& from) { - FloatParam::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(FloatParam* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information.FloatParam"; - } - protected: - explicit FloatParam(::google::protobuf::Arena* arena); - FloatParam(::google::protobuf::Arena* arena, const FloatParam& 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, - kShortDescriptionFieldNumber = 2, - kLongDescriptionFieldNumber = 3, - kUnitFieldNumber = 4, - kDecimalPlacesFieldNumber = 5, - kStartValueFieldNumber = 6, - kDefaultValueFieldNumber = 7, - kMinValueFieldNumber = 8, - kMaxValueFieldNumber = 9, - }; - // 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 short_description = 2; - void clear_short_description() ; - const std::string& short_description() const; - template - void set_short_description(Arg_&& arg, Args_... args); - std::string* mutable_short_description(); - PROTOBUF_NODISCARD std::string* release_short_description(); - void set_allocated_short_description(std::string* value); - - private: - const std::string& _internal_short_description() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_short_description( - const std::string& value); - std::string* _internal_mutable_short_description(); - - public: - // string long_description = 3; - void clear_long_description() ; - const std::string& long_description() const; - template - void set_long_description(Arg_&& arg, Args_... args); - std::string* mutable_long_description(); - PROTOBUF_NODISCARD std::string* release_long_description(); - void set_allocated_long_description(std::string* value); - - private: - const std::string& _internal_long_description() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_long_description( - const std::string& value); - std::string* _internal_mutable_long_description(); - - public: - // string unit = 4; - void clear_unit() ; - const std::string& unit() const; - template - void set_unit(Arg_&& arg, Args_... args); - std::string* mutable_unit(); - PROTOBUF_NODISCARD std::string* release_unit(); - void set_allocated_unit(std::string* value); - - private: - const std::string& _internal_unit() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_unit( - const std::string& value); - std::string* _internal_mutable_unit(); - - public: - // int32 decimal_places = 5; - void clear_decimal_places() ; - ::int32_t decimal_places() const; - void set_decimal_places(::int32_t value); - - private: - ::int32_t _internal_decimal_places() const; - void _internal_set_decimal_places(::int32_t value); - - public: - // float start_value = 6; - void clear_start_value() ; - float start_value() const; - void set_start_value(float value); - - private: - float _internal_start_value() const; - void _internal_set_start_value(float value); - - public: - // float default_value = 7; - void clear_default_value() ; - float default_value() const; - void set_default_value(float value); - - private: - float _internal_default_value() const; - void _internal_set_default_value(float value); - - public: - // float min_value = 8; - void clear_min_value() ; - float min_value() const; - void set_min_value(float value); - - private: - float _internal_min_value() const; - void _internal_set_min_value(float value); - - public: - // float max_value = 9; - void clear_max_value() ; - float max_value() const; - void set_max_value(float value); - - private: - float _internal_max_value() const; - void _internal_set_max_value(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParam) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 4, 9, 0, - 101, 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 short_description_; - ::google::protobuf::internal::ArenaStringPtr long_description_; - ::google::protobuf::internal::ArenaStringPtr unit_; - ::int32_t decimal_places_; - float start_value_; - float default_value_; - float min_value_; - float max_value_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_2fcomponent_5finformation_2eproto; -};// ------------------------------------------------------------------- - -class ComponentInformationResult final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information.ComponentInformationResult) */ { - public: - inline ComponentInformationResult() : ComponentInformationResult(nullptr) {} - ~ComponentInformationResult() override; - template - explicit PROTOBUF_CONSTEXPR ComponentInformationResult(::google::protobuf::internal::ConstantInitialized); - - inline ComponentInformationResult(const ComponentInformationResult& from) - : ComponentInformationResult(nullptr, from) {} - ComponentInformationResult(ComponentInformationResult&& from) noexcept - : ComponentInformationResult() { - *this = ::std::move(from); - } - - inline ComponentInformationResult& operator=(const ComponentInformationResult& from) { - CopyFrom(from); - return *this; - } - inline ComponentInformationResult& operator=(ComponentInformationResult&& 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 ComponentInformationResult& default_instance() { - return *internal_default_instance(); - } - static inline const ComponentInformationResult* internal_default_instance() { - return reinterpret_cast( - &_ComponentInformationResult_default_instance_); - } - static constexpr int kIndexInFileMessages = - 6; - - friend void swap(ComponentInformationResult& a, ComponentInformationResult& b) { - a.Swap(&b); - } - inline void Swap(ComponentInformationResult* 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(ComponentInformationResult* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - ComponentInformationResult* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ComponentInformationResult& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ComponentInformationResult& from) { - ComponentInformationResult::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(ComponentInformationResult* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information.ComponentInformationResult"; - } - protected: - explicit ComponentInformationResult(::google::protobuf::Arena* arena); - ComponentInformationResult(::google::protobuf::Arena* arena, const ComponentInformationResult& 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 = ComponentInformationResult_Result; - static constexpr Result RESULT_UNKNOWN = ComponentInformationResult_Result_RESULT_UNKNOWN; - static constexpr Result RESULT_SUCCESS = ComponentInformationResult_Result_RESULT_SUCCESS; - static constexpr Result RESULT_NO_SYSTEM = ComponentInformationResult_Result_RESULT_NO_SYSTEM; - static inline bool Result_IsValid(int value) { - return ComponentInformationResult_Result_IsValid(value); - } - static constexpr Result Result_MIN = ComponentInformationResult_Result_Result_MIN; - static constexpr Result Result_MAX = ComponentInformationResult_Result_Result_MAX; - static constexpr int Result_ARRAYSIZE = ComponentInformationResult_Result_Result_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* Result_descriptor() { - return ComponentInformationResult_Result_descriptor(); - } - template - static inline const std::string& Result_Name(T value) { - return ComponentInformationResult_Result_Name(value); - } - static inline bool Result_Parse(absl::string_view name, Result* value) { - return ComponentInformationResult_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.component_information.ComponentInformationResult.Result result = 1; - void clear_result() ; - ::mavsdk::rpc::component_information::ComponentInformationResult_Result result() const; - void set_result(::mavsdk::rpc::component_information::ComponentInformationResult_Result value); - - private: - ::mavsdk::rpc::component_information::ComponentInformationResult_Result _internal_result() const; - void _internal_set_result(::mavsdk::rpc::component_information::ComponentInformationResult_Result value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.ComponentInformationResult) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, - 78, 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_component_5finformation_2fcomponent_5finformation_2eproto; -};// ------------------------------------------------------------------- - -class AccessFloatParamsRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information.AccessFloatParamsRequest) */ { - public: - inline AccessFloatParamsRequest() : AccessFloatParamsRequest(nullptr) {} - template - explicit PROTOBUF_CONSTEXPR AccessFloatParamsRequest(::google::protobuf::internal::ConstantInitialized); - - inline AccessFloatParamsRequest(const AccessFloatParamsRequest& from) - : AccessFloatParamsRequest(nullptr, from) {} - AccessFloatParamsRequest(AccessFloatParamsRequest&& from) noexcept - : AccessFloatParamsRequest() { - *this = ::std::move(from); - } - - inline AccessFloatParamsRequest& operator=(const AccessFloatParamsRequest& from) { - CopyFrom(from); - return *this; - } - inline AccessFloatParamsRequest& operator=(AccessFloatParamsRequest&& 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 AccessFloatParamsRequest& default_instance() { - return *internal_default_instance(); - } - static inline const AccessFloatParamsRequest* internal_default_instance() { - return reinterpret_cast( - &_AccessFloatParamsRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 1; - - friend void swap(AccessFloatParamsRequest& a, AccessFloatParamsRequest& b) { - a.Swap(&b); - } - inline void Swap(AccessFloatParamsRequest* 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(AccessFloatParamsRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - AccessFloatParamsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const AccessFloatParamsRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const AccessFloatParamsRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); - } - public: - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information.AccessFloatParamsRequest"; - } - protected: - explicit AccessFloatParamsRequest(::google::protobuf::Arena* arena); - AccessFloatParamsRequest(::google::protobuf::Arena* arena, const AccessFloatParamsRequest& from); - public: - - ::google::protobuf::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.AccessFloatParamsRequest) - 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_component_5finformation_2fcomponent_5finformation_2eproto; -};// ------------------------------------------------------------------- - -class FloatParamResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information.FloatParamResponse) */ { - public: - inline FloatParamResponse() : FloatParamResponse(nullptr) {} - ~FloatParamResponse() override; - template - explicit PROTOBUF_CONSTEXPR FloatParamResponse(::google::protobuf::internal::ConstantInitialized); - - inline FloatParamResponse(const FloatParamResponse& from) - : FloatParamResponse(nullptr, from) {} - FloatParamResponse(FloatParamResponse&& from) noexcept - : FloatParamResponse() { - *this = ::std::move(from); - } - - inline FloatParamResponse& operator=(const FloatParamResponse& from) { - CopyFrom(from); - return *this; - } - inline FloatParamResponse& operator=(FloatParamResponse&& 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 FloatParamResponse& default_instance() { - return *internal_default_instance(); - } - static inline const FloatParamResponse* internal_default_instance() { - return reinterpret_cast( - &_FloatParamResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 5; - - friend void swap(FloatParamResponse& a, FloatParamResponse& b) { - a.Swap(&b); - } - inline void Swap(FloatParamResponse* 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(FloatParamResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - FloatParamResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FloatParamResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FloatParamResponse& from) { - FloatParamResponse::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(FloatParamResponse* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information.FloatParamResponse"; - } - protected: - explicit FloatParamResponse(::google::protobuf::Arena* arena); - FloatParamResponse(::google::protobuf::Arena* arena, const FloatParamResponse& 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 { - kParamUpdateFieldNumber = 1, - }; - // .mavsdk.rpc.component_information.FloatParamUpdate param_update = 1; - bool has_param_update() const; - void clear_param_update() ; - const ::mavsdk::rpc::component_information::FloatParamUpdate& param_update() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::component_information::FloatParamUpdate* release_param_update(); - ::mavsdk::rpc::component_information::FloatParamUpdate* mutable_param_update(); - void set_allocated_param_update(::mavsdk::rpc::component_information::FloatParamUpdate* value); - void unsafe_arena_set_allocated_param_update(::mavsdk::rpc::component_information::FloatParamUpdate* value); - ::mavsdk::rpc::component_information::FloatParamUpdate* unsafe_arena_release_param_update(); - - private: - const ::mavsdk::rpc::component_information::FloatParamUpdate& _internal_param_update() const; - ::mavsdk::rpc::component_information::FloatParamUpdate* _internal_mutable_param_update(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParamResponse) - 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::component_information::FloatParamUpdate* param_update_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_2fcomponent_5finformation_2eproto; -};// ------------------------------------------------------------------- - -class AccessFloatParamsResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information.AccessFloatParamsResponse) */ { - public: - inline AccessFloatParamsResponse() : AccessFloatParamsResponse(nullptr) {} - ~AccessFloatParamsResponse() override; - template - explicit PROTOBUF_CONSTEXPR AccessFloatParamsResponse(::google::protobuf::internal::ConstantInitialized); - - inline AccessFloatParamsResponse(const AccessFloatParamsResponse& from) - : AccessFloatParamsResponse(nullptr, from) {} - AccessFloatParamsResponse(AccessFloatParamsResponse&& from) noexcept - : AccessFloatParamsResponse() { - *this = ::std::move(from); - } - - inline AccessFloatParamsResponse& operator=(const AccessFloatParamsResponse& from) { - CopyFrom(from); - return *this; - } - inline AccessFloatParamsResponse& operator=(AccessFloatParamsResponse&& 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 AccessFloatParamsResponse& default_instance() { - return *internal_default_instance(); - } - static inline const AccessFloatParamsResponse* internal_default_instance() { - return reinterpret_cast( - &_AccessFloatParamsResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 2; - - friend void swap(AccessFloatParamsResponse& a, AccessFloatParamsResponse& b) { - a.Swap(&b); - } - inline void Swap(AccessFloatParamsResponse* 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(AccessFloatParamsResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - AccessFloatParamsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const AccessFloatParamsResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const AccessFloatParamsResponse& from) { - AccessFloatParamsResponse::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(AccessFloatParamsResponse* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information.AccessFloatParamsResponse"; - } - protected: - explicit AccessFloatParamsResponse(::google::protobuf::Arena* arena); - AccessFloatParamsResponse(::google::protobuf::Arena* arena, const AccessFloatParamsResponse& 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 { - kParamsFieldNumber = 2, - kComponentInformationResultFieldNumber = 1, - }; - // repeated .mavsdk.rpc.component_information.FloatParam params = 2; - int params_size() const; - private: - int _internal_params_size() const; - - public: - void clear_params() ; - ::mavsdk::rpc::component_information::FloatParam* mutable_params(int index); - ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::component_information::FloatParam >* - mutable_params(); - private: - const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_information::FloatParam>& _internal_params() const; - ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_information::FloatParam>* _internal_mutable_params(); - public: - const ::mavsdk::rpc::component_information::FloatParam& params(int index) const; - ::mavsdk::rpc::component_information::FloatParam* add_params(); - const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::component_information::FloatParam >& - params() const; - // .mavsdk.rpc.component_information.ComponentInformationResult component_information_result = 1; - bool has_component_information_result() const; - void clear_component_information_result() ; - const ::mavsdk::rpc::component_information::ComponentInformationResult& component_information_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::component_information::ComponentInformationResult* release_component_information_result(); - ::mavsdk::rpc::component_information::ComponentInformationResult* mutable_component_information_result(); - void set_allocated_component_information_result(::mavsdk::rpc::component_information::ComponentInformationResult* value); - void unsafe_arena_set_allocated_component_information_result(::mavsdk::rpc::component_information::ComponentInformationResult* value); - ::mavsdk::rpc::component_information::ComponentInformationResult* unsafe_arena_release_component_information_result(); - - private: - const ::mavsdk::rpc::component_information::ComponentInformationResult& _internal_component_information_result() const; - ::mavsdk::rpc::component_information::ComponentInformationResult* _internal_mutable_component_information_result(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.AccessFloatParamsResponse) - 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_; - ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::component_information::FloatParam > params_; - ::mavsdk::rpc::component_information::ComponentInformationResult* component_information_result_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_2fcomponent_5finformation_2eproto; -}; - -// =================================================================== - - - - -// =================================================================== - - -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wstrict-aliasing" -#endif // __GNUC__ -// ------------------------------------------------------------------- - -// FloatParam - -// string name = 1; -inline void FloatParam::clear_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.name_.ClearToEmpty(); -} -inline const std::string& FloatParam::name() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.name) - return _internal_name(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParam::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.component_information.FloatParam.name) -} -inline std::string* FloatParam::mutable_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_name(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.FloatParam.name) - return _s; -} -inline const std::string& FloatParam::_internal_name() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.name_.Get(); -} -inline void FloatParam::_internal_set_name(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.name_.Set(value, GetArena()); -} -inline std::string* FloatParam::_internal_mutable_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.name_.Mutable( GetArena()); -} -inline std::string* FloatParam::release_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information.FloatParam.name) - return _impl_.name_.Release(); -} -inline void FloatParam::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.component_information.FloatParam.name) -} - -// string short_description = 2; -inline void FloatParam::clear_short_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.short_description_.ClearToEmpty(); -} -inline const std::string& FloatParam::short_description() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.short_description) - return _internal_short_description(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParam::set_short_description(Arg_&& arg, - Args_... args) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.short_description_.Set(static_cast(arg), args..., GetArena()); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParam.short_description) -} -inline std::string* FloatParam::mutable_short_description() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_short_description(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.FloatParam.short_description) - return _s; -} -inline const std::string& FloatParam::_internal_short_description() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.short_description_.Get(); -} -inline void FloatParam::_internal_set_short_description(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.short_description_.Set(value, GetArena()); -} -inline std::string* FloatParam::_internal_mutable_short_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.short_description_.Mutable( GetArena()); -} -inline std::string* FloatParam::release_short_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information.FloatParam.short_description) - return _impl_.short_description_.Release(); -} -inline void FloatParam::set_allocated_short_description(std::string* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.short_description_.SetAllocated(value, GetArena()); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (_impl_.short_description_.IsDefault()) { - _impl_.short_description_.Set("", GetArena()); - } - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information.FloatParam.short_description) -} - -// string long_description = 3; -inline void FloatParam::clear_long_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.long_description_.ClearToEmpty(); -} -inline const std::string& FloatParam::long_description() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.long_description) - return _internal_long_description(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParam::set_long_description(Arg_&& arg, - Args_... args) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.long_description_.Set(static_cast(arg), args..., GetArena()); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParam.long_description) -} -inline std::string* FloatParam::mutable_long_description() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_long_description(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.FloatParam.long_description) - return _s; -} -inline const std::string& FloatParam::_internal_long_description() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.long_description_.Get(); -} -inline void FloatParam::_internal_set_long_description(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.long_description_.Set(value, GetArena()); -} -inline std::string* FloatParam::_internal_mutable_long_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.long_description_.Mutable( GetArena()); -} -inline std::string* FloatParam::release_long_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information.FloatParam.long_description) - return _impl_.long_description_.Release(); -} -inline void FloatParam::set_allocated_long_description(std::string* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.long_description_.SetAllocated(value, GetArena()); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (_impl_.long_description_.IsDefault()) { - _impl_.long_description_.Set("", GetArena()); - } - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information.FloatParam.long_description) -} - -// string unit = 4; -inline void FloatParam::clear_unit() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.unit_.ClearToEmpty(); -} -inline const std::string& FloatParam::unit() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.unit) - return _internal_unit(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParam::set_unit(Arg_&& arg, - Args_... args) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.unit_.Set(static_cast(arg), args..., GetArena()); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParam.unit) -} -inline std::string* FloatParam::mutable_unit() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_unit(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.FloatParam.unit) - return _s; -} -inline const std::string& FloatParam::_internal_unit() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.unit_.Get(); -} -inline void FloatParam::_internal_set_unit(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.unit_.Set(value, GetArena()); -} -inline std::string* FloatParam::_internal_mutable_unit() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.unit_.Mutable( GetArena()); -} -inline std::string* FloatParam::release_unit() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information.FloatParam.unit) - return _impl_.unit_.Release(); -} -inline void FloatParam::set_allocated_unit(std::string* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.unit_.SetAllocated(value, GetArena()); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (_impl_.unit_.IsDefault()) { - _impl_.unit_.Set("", GetArena()); - } - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information.FloatParam.unit) -} - -// int32 decimal_places = 5; -inline void FloatParam::clear_decimal_places() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.decimal_places_ = 0; -} -inline ::int32_t FloatParam::decimal_places() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.decimal_places) - return _internal_decimal_places(); -} -inline void FloatParam::set_decimal_places(::int32_t value) { - _internal_set_decimal_places(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParam.decimal_places) -} -inline ::int32_t FloatParam::_internal_decimal_places() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.decimal_places_; -} -inline void FloatParam::_internal_set_decimal_places(::int32_t value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.decimal_places_ = value; -} - -// float start_value = 6; -inline void FloatParam::clear_start_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.start_value_ = 0; -} -inline float FloatParam::start_value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.start_value) - return _internal_start_value(); -} -inline void FloatParam::set_start_value(float value) { - _internal_set_start_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParam.start_value) -} -inline float FloatParam::_internal_start_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.start_value_; -} -inline void FloatParam::_internal_set_start_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.start_value_ = value; -} - -// float default_value = 7; -inline void FloatParam::clear_default_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.default_value_ = 0; -} -inline float FloatParam::default_value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.default_value) - return _internal_default_value(); -} -inline void FloatParam::set_default_value(float value) { - _internal_set_default_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParam.default_value) -} -inline float FloatParam::_internal_default_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.default_value_; -} -inline void FloatParam::_internal_set_default_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.default_value_ = value; -} - -// float min_value = 8; -inline void FloatParam::clear_min_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.min_value_ = 0; -} -inline float FloatParam::min_value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.min_value) - return _internal_min_value(); -} -inline void FloatParam::set_min_value(float value) { - _internal_set_min_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParam.min_value) -} -inline float FloatParam::_internal_min_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.min_value_; -} -inline void FloatParam::_internal_set_min_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.min_value_ = value; -} - -// float max_value = 9; -inline void FloatParam::clear_max_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.max_value_ = 0; -} -inline float FloatParam::max_value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParam.max_value) - return _internal_max_value(); -} -inline void FloatParam::set_max_value(float value) { - _internal_set_max_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParam.max_value) -} -inline float FloatParam::_internal_max_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.max_value_; -} -inline void FloatParam::_internal_set_max_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.max_value_ = value; -} - -// ------------------------------------------------------------------- - -// AccessFloatParamsRequest - -// ------------------------------------------------------------------- - -// AccessFloatParamsResponse - -// .mavsdk.rpc.component_information.ComponentInformationResult component_information_result = 1; -inline bool AccessFloatParamsResponse::has_component_information_result() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.component_information_result_ != nullptr); - return value; -} -inline void AccessFloatParamsResponse::clear_component_information_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.component_information_result_ != nullptr) _impl_.component_information_result_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::component_information::ComponentInformationResult& AccessFloatParamsResponse::_internal_component_information_result() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::component_information::ComponentInformationResult* p = _impl_.component_information_result_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::component_information::_ComponentInformationResult_default_instance_); -} -inline const ::mavsdk::rpc::component_information::ComponentInformationResult& AccessFloatParamsResponse::component_information_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.AccessFloatParamsResponse.component_information_result) - return _internal_component_information_result(); -} -inline void AccessFloatParamsResponse::unsafe_arena_set_allocated_component_information_result(::mavsdk::rpc::component_information::ComponentInformationResult* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.component_information_result_); - } - _impl_.component_information_result_ = reinterpret_cast<::mavsdk::rpc::component_information::ComponentInformationResult*>(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.component_information.AccessFloatParamsResponse.component_information_result) -} -inline ::mavsdk::rpc::component_information::ComponentInformationResult* AccessFloatParamsResponse::release_component_information_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information::ComponentInformationResult* released = _impl_.component_information_result_; - _impl_.component_information_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::component_information::ComponentInformationResult* AccessFloatParamsResponse::unsafe_arena_release_component_information_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information.AccessFloatParamsResponse.component_information_result) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information::ComponentInformationResult* temp = _impl_.component_information_result_; - _impl_.component_information_result_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::component_information::ComponentInformationResult* AccessFloatParamsResponse::_internal_mutable_component_information_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.component_information_result_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::component_information::ComponentInformationResult>(GetArena()); - _impl_.component_information_result_ = reinterpret_cast<::mavsdk::rpc::component_information::ComponentInformationResult*>(p); - } - return _impl_.component_information_result_; -} -inline ::mavsdk::rpc::component_information::ComponentInformationResult* AccessFloatParamsResponse::mutable_component_information_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::component_information::ComponentInformationResult* _msg = _internal_mutable_component_information_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.AccessFloatParamsResponse.component_information_result) - return _msg; -} -inline void AccessFloatParamsResponse::set_allocated_component_information_result(::mavsdk::rpc::component_information::ComponentInformationResult* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::component_information::ComponentInformationResult*>(_impl_.component_information_result_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::component_information::ComponentInformationResult*>(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_.component_information_result_ = reinterpret_cast<::mavsdk::rpc::component_information::ComponentInformationResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information.AccessFloatParamsResponse.component_information_result) -} - -// repeated .mavsdk.rpc.component_information.FloatParam params = 2; -inline int AccessFloatParamsResponse::_internal_params_size() const { - return _internal_params().size(); -} -inline int AccessFloatParamsResponse::params_size() const { - return _internal_params_size(); -} -inline void AccessFloatParamsResponse::clear_params() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.params_.Clear(); -} -inline ::mavsdk::rpc::component_information::FloatParam* AccessFloatParamsResponse::mutable_params(int index) - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.AccessFloatParamsResponse.params) - return _internal_mutable_params()->Mutable(index); -} -inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_information::FloatParam>* AccessFloatParamsResponse::mutable_params() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.component_information.AccessFloatParamsResponse.params) - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - return _internal_mutable_params(); -} -inline const ::mavsdk::rpc::component_information::FloatParam& AccessFloatParamsResponse::params(int index) const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.AccessFloatParamsResponse.params) - return _internal_params().Get(index); -} -inline ::mavsdk::rpc::component_information::FloatParam* AccessFloatParamsResponse::add_params() ABSL_ATTRIBUTE_LIFETIME_BOUND { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ::mavsdk::rpc::component_information::FloatParam* _add = _internal_mutable_params()->Add(); - // @@protoc_insertion_point(field_add:mavsdk.rpc.component_information.AccessFloatParamsResponse.params) - return _add; -} -inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_information::FloatParam>& AccessFloatParamsResponse::params() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_list:mavsdk.rpc.component_information.AccessFloatParamsResponse.params) - return _internal_params(); -} -inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_information::FloatParam>& -AccessFloatParamsResponse::_internal_params() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.params_; -} -inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::component_information::FloatParam>* -AccessFloatParamsResponse::_internal_mutable_params() { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return &_impl_.params_; -} - -// ------------------------------------------------------------------- - -// FloatParamUpdate - -// string name = 1; -inline void FloatParamUpdate::clear_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.name_.ClearToEmpty(); -} -inline const std::string& FloatParamUpdate::name() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParamUpdate.name) - return _internal_name(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParamUpdate::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.component_information.FloatParamUpdate.name) -} -inline std::string* FloatParamUpdate::mutable_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_name(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.FloatParamUpdate.name) - return _s; -} -inline const std::string& FloatParamUpdate::_internal_name() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.name_.Get(); -} -inline void FloatParamUpdate::_internal_set_name(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.name_.Set(value, GetArena()); -} -inline std::string* FloatParamUpdate::_internal_mutable_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.name_.Mutable( GetArena()); -} -inline std::string* FloatParamUpdate::release_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information.FloatParamUpdate.name) - return _impl_.name_.Release(); -} -inline void FloatParamUpdate::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.component_information.FloatParamUpdate.name) -} - -// float value = 2; -inline void FloatParamUpdate::clear_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.value_ = 0; -} -inline float FloatParamUpdate::value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParamUpdate.value) - return _internal_value(); -} -inline void FloatParamUpdate::set_value(float value) { - _internal_set_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.FloatParamUpdate.value) -} -inline float FloatParamUpdate::_internal_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.value_; -} -inline void FloatParamUpdate::_internal_set_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.value_ = value; -} - -// ------------------------------------------------------------------- - -// SubscribeFloatParamRequest - -// ------------------------------------------------------------------- - -// FloatParamResponse - -// .mavsdk.rpc.component_information.FloatParamUpdate param_update = 1; -inline bool FloatParamResponse::has_param_update() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.param_update_ != nullptr); - return value; -} -inline void FloatParamResponse::clear_param_update() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.param_update_ != nullptr) _impl_.param_update_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::component_information::FloatParamUpdate& FloatParamResponse::_internal_param_update() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::component_information::FloatParamUpdate* p = _impl_.param_update_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::component_information::_FloatParamUpdate_default_instance_); -} -inline const ::mavsdk::rpc::component_information::FloatParamUpdate& FloatParamResponse::param_update() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.FloatParamResponse.param_update) - return _internal_param_update(); -} -inline void FloatParamResponse::unsafe_arena_set_allocated_param_update(::mavsdk::rpc::component_information::FloatParamUpdate* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.param_update_); - } - _impl_.param_update_ = reinterpret_cast<::mavsdk::rpc::component_information::FloatParamUpdate*>(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.component_information.FloatParamResponse.param_update) -} -inline ::mavsdk::rpc::component_information::FloatParamUpdate* FloatParamResponse::release_param_update() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information::FloatParamUpdate* released = _impl_.param_update_; - _impl_.param_update_ = 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::component_information::FloatParamUpdate* FloatParamResponse::unsafe_arena_release_param_update() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information.FloatParamResponse.param_update) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information::FloatParamUpdate* temp = _impl_.param_update_; - _impl_.param_update_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::component_information::FloatParamUpdate* FloatParamResponse::_internal_mutable_param_update() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.param_update_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::component_information::FloatParamUpdate>(GetArena()); - _impl_.param_update_ = reinterpret_cast<::mavsdk::rpc::component_information::FloatParamUpdate*>(p); - } - return _impl_.param_update_; -} -inline ::mavsdk::rpc::component_information::FloatParamUpdate* FloatParamResponse::mutable_param_update() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::component_information::FloatParamUpdate* _msg = _internal_mutable_param_update(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.FloatParamResponse.param_update) - return _msg; -} -inline void FloatParamResponse::set_allocated_param_update(::mavsdk::rpc::component_information::FloatParamUpdate* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::component_information::FloatParamUpdate*>(_impl_.param_update_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::component_information::FloatParamUpdate*>(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_.param_update_ = reinterpret_cast<::mavsdk::rpc::component_information::FloatParamUpdate*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information.FloatParamResponse.param_update) -} - -// ------------------------------------------------------------------- - -// ComponentInformationResult - -// .mavsdk.rpc.component_information.ComponentInformationResult.Result result = 1; -inline void ComponentInformationResult::clear_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.result_ = 0; -} -inline ::mavsdk::rpc::component_information::ComponentInformationResult_Result ComponentInformationResult::result() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.ComponentInformationResult.result) - return _internal_result(); -} -inline void ComponentInformationResult::set_result(::mavsdk::rpc::component_information::ComponentInformationResult_Result value) { - _internal_set_result(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information.ComponentInformationResult.result) -} -inline ::mavsdk::rpc::component_information::ComponentInformationResult_Result ComponentInformationResult::_internal_result() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::component_information::ComponentInformationResult_Result>(_impl_.result_); -} -inline void ComponentInformationResult::_internal_set_result(::mavsdk::rpc::component_information::ComponentInformationResult_Result value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.result_ = value; -} - -// string result_str = 2; -inline void ComponentInformationResult::clear_result_str() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.result_str_.ClearToEmpty(); -} -inline const std::string& ComponentInformationResult::result_str() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information.ComponentInformationResult.result_str) - return _internal_result_str(); -} -template -inline PROTOBUF_ALWAYS_INLINE void ComponentInformationResult::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.component_information.ComponentInformationResult.result_str) -} -inline std::string* ComponentInformationResult::mutable_result_str() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_result_str(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information.ComponentInformationResult.result_str) - return _s; -} -inline const std::string& ComponentInformationResult::_internal_result_str() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.result_str_.Get(); -} -inline void ComponentInformationResult::_internal_set_result_str(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.result_str_.Set(value, GetArena()); -} -inline std::string* ComponentInformationResult::_internal_mutable_result_str() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.result_str_.Mutable( GetArena()); -} -inline std::string* ComponentInformationResult::release_result_str() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information.ComponentInformationResult.result_str) - return _impl_.result_str_.Release(); -} -inline void ComponentInformationResult::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.component_information.ComponentInformationResult.result_str) -} - -#ifdef __GNUC__ -#pragma GCC diagnostic pop -#endif // __GNUC__ - -// @@protoc_insertion_point(namespace_scope) -} // namespace component_information -} // namespace rpc -} // namespace mavsdk - - -namespace google { -namespace protobuf { - -template <> -struct is_proto_enum<::mavsdk::rpc::component_information::ComponentInformationResult_Result> : std::true_type {}; -template <> -inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::component_information::ComponentInformationResult_Result>() { - return ::mavsdk::rpc::component_information::ComponentInformationResult_Result_descriptor(); -} - -} // namespace protobuf -} // namespace google - -// @@protoc_insertion_point(global_scope) - -#include "google/protobuf/port_undef.inc" - -#endif // GOOGLE_PROTOBUF_INCLUDED_component_5finformation_2fcomponent_5finformation_2eproto_2epb_2eh diff --git a/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.cc b/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.cc deleted file mode 100644 index fe588af19d..0000000000 --- a/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.cc +++ /dev/null @@ -1,125 +0,0 @@ -// Generated by the gRPC C++ plugin. -// If you make any local change, they will be lost. -// source: component_information_server/component_information_server.proto - -#include "component_information_server/component_information_server.pb.h" -#include "component_information_server/component_information_server.grpc.pb.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -namespace mavsdk { -namespace rpc { -namespace component_information_server { - -static const char* ComponentInformationServerService_method_names[] = { - "/mavsdk.rpc.component_information_server.ComponentInformationServerService/ProvideFloatParam", - "/mavsdk.rpc.component_information_server.ComponentInformationServerService/SubscribeFloatParam", -}; - -std::unique_ptr< ComponentInformationServerService::Stub> ComponentInformationServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { - (void)options; - std::unique_ptr< ComponentInformationServerService::Stub> stub(new ComponentInformationServerService::Stub(channel, options)); - return stub; -} - -ComponentInformationServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) - : channel_(channel), rpcmethod_ProvideFloatParam_(ComponentInformationServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeFloatParam_(ComponentInformationServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - {} - -::grpc::Status ComponentInformationServerService::Stub::ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_ProvideFloatParam_, context, request, response); -} - -void ComponentInformationServerService::Stub::async::ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ProvideFloatParam_, context, request, response, std::move(f)); -} - -void ComponentInformationServerService::Stub::async::ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ProvideFloatParam_, context, request, response, reactor); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* ComponentInformationServerService::Stub::PrepareAsyncProvideFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse, ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_ProvideFloatParam_, context, request); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* ComponentInformationServerService::Stub::AsyncProvideFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - auto* result = - this->PrepareAsyncProvideFloatParamRaw(context, request, cq); - result->StartCall(); - return result; -} - -::grpc::ClientReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>* ComponentInformationServerService::Stub::SubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request) { - return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::component_information_server::FloatParamResponse>::Create(channel_.get(), rpcmethod_SubscribeFloatParam_, context, request); -} - -void ComponentInformationServerService::Stub::async::SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_information_server::FloatParamResponse>* reactor) { - ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::component_information_server::FloatParamResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeFloatParam_, context, request, reactor); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>* ComponentInformationServerService::Stub::AsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::component_information_server::FloatParamResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeFloatParam_, context, request, true, tag); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>* ComponentInformationServerService::Stub::PrepareAsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::component_information_server::FloatParamResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeFloatParam_, context, request, false, nullptr); -} - -ComponentInformationServerService::Service::Service() { - AddMethod(new ::grpc::internal::RpcServiceMethod( - ComponentInformationServerService_method_names[0], - ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< ComponentInformationServerService::Service, ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( - [](ComponentInformationServerService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* req, - ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* resp) { - return service->ProvideFloatParam(ctx, req, resp); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - ComponentInformationServerService_method_names[1], - ::grpc::internal::RpcMethod::SERVER_STREAMING, - new ::grpc::internal::ServerStreamingHandler< ComponentInformationServerService::Service, ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest, ::mavsdk::rpc::component_information_server::FloatParamResponse>( - [](ComponentInformationServerService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* req, - ::grpc::ServerWriter<::mavsdk::rpc::component_information_server::FloatParamResponse>* writer) { - return service->SubscribeFloatParam(ctx, req, writer); - }, this))); -} - -ComponentInformationServerService::Service::~Service() { -} - -::grpc::Status ComponentInformationServerService::Service::ProvideFloatParam(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response) { - (void) context; - (void) request; - (void) response; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - -::grpc::Status ComponentInformationServerService::Service::SubscribeFloatParam(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* writer) { - (void) context; - (void) request; - (void) writer; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - - -} // namespace mavsdk -} // namespace rpc -} // namespace component_information_server - diff --git a/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.h b/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.h deleted file mode 100644 index 0466be535b..0000000000 --- a/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.h +++ /dev/null @@ -1,413 +0,0 @@ -// Generated by the gRPC C++ plugin. -// If you make any local change, they will be lost. -// source: component_information_server/component_information_server.proto -#ifndef GRPC_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto__INCLUDED -#define GRPC_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto__INCLUDED - -#include "component_information_server/component_information_server.pb.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -namespace mavsdk { -namespace rpc { -namespace component_information_server { - -// Provide component information such as parameters. -class ComponentInformationServerService final { - public: - static constexpr char const* service_full_name() { - return "mavsdk.rpc.component_information_server.ComponentInformationServerService"; - } - class StubInterface { - public: - virtual ~StubInterface() {} - // - // Provide a param of type float. - virtual ::grpc::Status ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>> AsyncProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>>(AsyncProvideFloatParamRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>> PrepareAsyncProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>>(PrepareAsyncProvideFloatParamRaw(context, request, cq)); - } - // - // Subscribe to float param updates. - std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>> SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request) { - return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>>(SubscribeFloatParamRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>> AsyncSubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>>(AsyncSubscribeFloatParamRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>> PrepareAsyncSubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>>(PrepareAsyncSubscribeFloatParamRaw(context, request, cq)); - } - class async_interface { - public: - virtual ~async_interface() {} - // - // Provide a param of type float. - virtual void ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response, std::function) = 0; - virtual void ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // - // Subscribe to float param updates. - virtual void SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_information_server::FloatParamResponse>* reactor) = 0; - }; - typedef class async_interface experimental_async_interface; - virtual class async_interface* async() { return nullptr; } - class async_interface* experimental_async() { return async(); } - private: - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* AsyncProvideFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* PrepareAsyncProvideFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>* SubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>* AsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::component_information_server::FloatParamResponse>* PrepareAsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) = 0; - }; - class Stub final : public StubInterface { - public: - Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); - ::grpc::Status ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>> AsyncProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>>(AsyncProvideFloatParamRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>> PrepareAsyncProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>>(PrepareAsyncProvideFloatParamRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>> SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request) { - return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>>(SubscribeFloatParamRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>> AsyncSubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>>(AsyncSubscribeFloatParamRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>> PrepareAsyncSubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>>(PrepareAsyncSubscribeFloatParamRaw(context, request, cq)); - } - class async final : - public StubInterface::async_interface { - public: - void ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response, std::function) override; - void ProvideFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response, ::grpc::ClientUnaryReactor* reactor) override; - void SubscribeFloatParam(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::component_information_server::FloatParamResponse>* reactor) override; - private: - friend class Stub; - explicit async(Stub* stub): stub_(stub) { } - Stub* stub() { return stub_; } - Stub* stub_; - }; - class async* async() override { return &async_stub_; } - - private: - std::shared_ptr< ::grpc::ChannelInterface> channel_; - class async async_stub_{this}; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* AsyncProvideFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* PrepareAsyncProvideFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>* SubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>* AsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::component_information_server::FloatParamResponse>* PrepareAsyncSubscribeFloatParamRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest& request, ::grpc::CompletionQueue* cq) override; - const ::grpc::internal::RpcMethod rpcmethod_ProvideFloatParam_; - const ::grpc::internal::RpcMethod rpcmethod_SubscribeFloatParam_; - }; - 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(); - // - // Provide a param of type float. - virtual ::grpc::Status ProvideFloatParam(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response); - // - // Subscribe to float param updates. - virtual ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* writer); - }; - template - class WithAsyncMethod_ProvideFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_ProvideFloatParam() { - ::grpc::Service::MarkMethodAsync(0); - } - ~WithAsyncMethod_ProvideFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status ProvideFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestProvideFloatParam(::grpc::ServerContext* context, ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithAsyncMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodAsync(1); - } - ~WithAsyncMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeFloatParam(::grpc::ServerContext* context, ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* 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); - } - }; - typedef WithAsyncMethod_ProvideFloatParam > AsyncService; - template - class WithCallbackMethod_ProvideFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_ProvideFloatParam() { - ::grpc::Service::MarkMethodCallback(0, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* request, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* response) { return this->ProvideFloatParam(context, request, response); }));} - void SetMessageAllocatorFor_ProvideFloatParam( - ::grpc::MessageAllocator< ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>*>(handler) - ->SetMessageAllocator(allocator); - } - ~WithCallbackMethod_ProvideFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status ProvideFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* ProvideFloatParam( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* /*response*/) { return nullptr; } - }; - template - class WithCallbackMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodCallback(1, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest, ::mavsdk::rpc::component_information_server::FloatParamResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* request) { return this->SubscribeFloatParam(context, request); })); - } - ~WithCallbackMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::component_information_server::FloatParamResponse>* SubscribeFloatParam( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* /*request*/) { return nullptr; } - }; - typedef WithCallbackMethod_ProvideFloatParam > CallbackService; - typedef CallbackService ExperimentalCallbackService; - template - class WithGenericMethod_ProvideFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_ProvideFloatParam() { - ::grpc::Service::MarkMethodGeneric(0); - } - ~WithGenericMethod_ProvideFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status ProvideFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template - class WithGenericMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodGeneric(1); - } - ~WithGenericMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template - class WithRawMethod_ProvideFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_ProvideFloatParam() { - ::grpc::Service::MarkMethodRaw(0); - } - ~WithRawMethod_ProvideFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status ProvideFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestProvideFloatParam(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodRaw(1); - } - ~WithRawMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeFloatParam(::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 WithRawCallbackMethod_ProvideFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_ProvideFloatParam() { - ::grpc::Service::MarkMethodRawCallback(0, - new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ProvideFloatParam(context, request, response); })); - } - ~WithRawCallbackMethod_ProvideFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status ProvideFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* ProvideFloatParam( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } - }; - template - class WithRawCallbackMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodRawCallback(1, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeFloatParam(context, request); })); - } - ~WithRawCallbackMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeFloatParam( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } - }; - template - class WithStreamedUnaryMethod_ProvideFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithStreamedUnaryMethod_ProvideFloatParam() { - ::grpc::Service::MarkMethodStreamed(0, - new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* streamer) { - return this->StreamedProvideFloatParam(context, - streamer); - })); - } - ~WithStreamedUnaryMethod_ProvideFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status ProvideFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvideFloatParamResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with streamed unary - virtual ::grpc::Status StreamedProvideFloatParam(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::component_information_server::ProvideFloatParamRequest,::mavsdk::rpc::component_information_server::ProvideFloatParamResponse>* server_unary_streamer) = 0; - }; - typedef WithStreamedUnaryMethod_ProvideFloatParam StreamedUnaryService; - template - class WithSplitStreamingMethod_SubscribeFloatParam : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithSplitStreamingMethod_SubscribeFloatParam() { - ::grpc::Service::MarkMethodStreamed(1, - new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest, ::mavsdk::rpc::component_information_server::FloatParamResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest, ::mavsdk::rpc::component_information_server::FloatParamResponse>* streamer) { - return this->StreamedSubscribeFloatParam(context, - streamer); - })); - } - ~WithSplitStreamingMethod_SubscribeFloatParam() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SubscribeFloatParam(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::component_information_server::FloatParamResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeFloatParam(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest,::mavsdk::rpc::component_information_server::FloatParamResponse>* server_split_streamer) = 0; - }; - typedef WithSplitStreamingMethod_SubscribeFloatParam SplitStreamedService; - typedef WithStreamedUnaryMethod_ProvideFloatParam > StreamedService; -}; - -} // namespace component_information_server -} // namespace rpc -} // namespace mavsdk - - -#endif // GRPC_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto__INCLUDED diff --git a/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.cc b/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.cc deleted file mode 100644 index 5c84cc082c..0000000000 --- a/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.cc +++ /dev/null @@ -1,1973 +0,0 @@ -// Generated by the protocol buffer compiler. DO NOT EDIT! -// source: component_information_server/component_information_server.proto - -#include "component_information_server/component_information_server.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 component_information_server { - template -PROTOBUF_CONSTEXPR SubscribeFloatParamRequest::SubscribeFloatParamRequest(::_pbi::ConstantInitialized) {} -struct SubscribeFloatParamRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SubscribeFloatParamRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SubscribeFloatParamRequestDefaultTypeInternal() {} - union { - SubscribeFloatParamRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeFloatParamRequestDefaultTypeInternal _SubscribeFloatParamRequest_default_instance_; - -inline constexpr FloatParamUpdate::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : name_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - value_{0}, - _cached_size_{0} {} - -template -PROTOBUF_CONSTEXPR FloatParamUpdate::FloatParamUpdate(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct FloatParamUpdateDefaultTypeInternal { - PROTOBUF_CONSTEXPR FloatParamUpdateDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~FloatParamUpdateDefaultTypeInternal() {} - union { - FloatParamUpdate _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FloatParamUpdateDefaultTypeInternal _FloatParamUpdate_default_instance_; - -inline constexpr FloatParam::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : name_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - short_description_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - long_description_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - unit_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - decimal_places_{0}, - start_value_{0}, - default_value_{0}, - min_value_{0}, - max_value_{0}, - _cached_size_{0} {} - -template -PROTOBUF_CONSTEXPR FloatParam::FloatParam(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct FloatParamDefaultTypeInternal { - PROTOBUF_CONSTEXPR FloatParamDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~FloatParamDefaultTypeInternal() {} - union { - FloatParam _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FloatParamDefaultTypeInternal _FloatParam_default_instance_; - -inline constexpr ComponentInformationServerResult::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : result_str_( - &::google::protobuf::internal::fixed_address_empty_string, - ::_pbi::ConstantInitialized()), - result_{static_cast< ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result >(0)}, - _cached_size_{0} {} - -template -PROTOBUF_CONSTEXPR ComponentInformationServerResult::ComponentInformationServerResult(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct ComponentInformationServerResultDefaultTypeInternal { - PROTOBUF_CONSTEXPR ComponentInformationServerResultDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~ComponentInformationServerResultDefaultTypeInternal() {} - union { - ComponentInformationServerResult _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ComponentInformationServerResultDefaultTypeInternal _ComponentInformationServerResult_default_instance_; - -inline constexpr ProvideFloatParamResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - component_information_server_result_{nullptr} {} - -template -PROTOBUF_CONSTEXPR ProvideFloatParamResponse::ProvideFloatParamResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct ProvideFloatParamResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR ProvideFloatParamResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~ProvideFloatParamResponseDefaultTypeInternal() {} - union { - ProvideFloatParamResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ProvideFloatParamResponseDefaultTypeInternal _ProvideFloatParamResponse_default_instance_; - -inline constexpr ProvideFloatParamRequest::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - param_{nullptr} {} - -template -PROTOBUF_CONSTEXPR ProvideFloatParamRequest::ProvideFloatParamRequest(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct ProvideFloatParamRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR ProvideFloatParamRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~ProvideFloatParamRequestDefaultTypeInternal() {} - union { - ProvideFloatParamRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ProvideFloatParamRequestDefaultTypeInternal _ProvideFloatParamRequest_default_instance_; - -inline constexpr FloatParamResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - param_update_{nullptr} {} - -template -PROTOBUF_CONSTEXPR FloatParamResponse::FloatParamResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct FloatParamResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR FloatParamResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~FloatParamResponseDefaultTypeInternal() {} - union { - FloatParamResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FloatParamResponseDefaultTypeInternal _FloatParamResponse_default_instance_; -} // namespace component_information_server -} // namespace rpc -} // namespace mavsdk -static ::_pb::Metadata file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[7]; -static const ::_pb::EnumDescriptor* file_level_enum_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[1]; -static constexpr const ::_pb::ServiceDescriptor** - file_level_service_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto = nullptr; -const ::uint32_t TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( - protodesc_cold) = { - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _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::component_information_server::FloatParam, _impl_.name_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _impl_.short_description_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _impl_.long_description_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _impl_.unit_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _impl_.decimal_places_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _impl_.start_value_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _impl_.default_value_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _impl_.min_value_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParam, _impl_.max_value_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ProvideFloatParamRequest, _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::component_information_server::ProvideFloatParamRequest, _impl_.param_), - 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ProvideFloatParamResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ProvideFloatParamResponse, _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::component_information_server::ProvideFloatParamResponse, _impl_.component_information_server_result_), - 0, - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParamUpdate, _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::component_information_server::FloatParamUpdate, _impl_.name_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParamUpdate, _impl_.value_), - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest, _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::component_information_server::FloatParamResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::FloatParamResponse, _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::component_information_server::FloatParamResponse, _impl_.param_update_), - 0, - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ComponentInformationServerResult, _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::component_information_server::ComponentInformationServerResult, _impl_.result_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ComponentInformationServerResult, _impl_.result_str_), -}; - -static const ::_pbi::MigrationSchema - schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { - {0, -1, -1, sizeof(::mavsdk::rpc::component_information_server::FloatParam)}, - {17, 26, -1, sizeof(::mavsdk::rpc::component_information_server::ProvideFloatParamRequest)}, - {27, 36, -1, sizeof(::mavsdk::rpc::component_information_server::ProvideFloatParamResponse)}, - {37, -1, -1, sizeof(::mavsdk::rpc::component_information_server::FloatParamUpdate)}, - {47, -1, -1, sizeof(::mavsdk::rpc::component_information_server::SubscribeFloatParamRequest)}, - {55, 64, -1, sizeof(::mavsdk::rpc::component_information_server::FloatParamResponse)}, - {65, -1, -1, sizeof(::mavsdk::rpc::component_information_server::ComponentInformationServerResult)}, -}; - -static const ::_pb::Message* const file_default_instances[] = { - &::mavsdk::rpc::component_information_server::_FloatParam_default_instance_._instance, - &::mavsdk::rpc::component_information_server::_ProvideFloatParamRequest_default_instance_._instance, - &::mavsdk::rpc::component_information_server::_ProvideFloatParamResponse_default_instance_._instance, - &::mavsdk::rpc::component_information_server::_FloatParamUpdate_default_instance_._instance, - &::mavsdk::rpc::component_information_server::_SubscribeFloatParamRequest_default_instance_._instance, - &::mavsdk::rpc::component_information_server::_FloatParamResponse_default_instance_._instance, - &::mavsdk::rpc::component_information_server::_ComponentInformationServerResult_default_instance_._instance, -}; -const char descriptor_table_protodef_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { - "\n\?component_information_server/component" - "_information_server.proto\022\'mavsdk.rpc.co" - "mponent_information_server\032\024mavsdk_optio" - "ns.proto\"\307\001\n\nFloatParam\022\014\n\004name\030\001 \001(\t\022\031\n" - "\021short_description\030\002 \001(\t\022\030\n\020long_descrip" - "tion\030\003 \001(\t\022\014\n\004unit\030\004 \001(\t\022\026\n\016decimal_plac" - "es\030\005 \001(\005\022\023\n\013start_value\030\006 \001(\002\022\025\n\rdefault" - "_value\030\007 \001(\002\022\021\n\tmin_value\030\010 \001(\002\022\021\n\tmax_v" - "alue\030\t \001(\002\"^\n\030ProvideFloatParamRequest\022B" - "\n\005param\030\001 \001(\01323.mavsdk.rpc.component_inf" - "ormation_server.FloatParam\"\223\001\n\031ProvideFl" - "oatParamResponse\022v\n#component_informatio" - "n_server_result\030\001 \001(\0132I.mavsdk.rpc.compo" - "nent_information_server.ComponentInforma" - "tionServerResult\"/\n\020FloatParamUpdate\022\014\n\004" - "name\030\001 \001(\t\022\r\n\005value\030\002 \001(\002\"\034\n\032SubscribeFl" - "oatParamRequest\"e\n\022FloatParamResponse\022O\n" - "\014param_update\030\001 \001(\01329.mavsdk.rpc.compone" - "nt_information_server.FloatParamUpdate\"\352" - "\002\n ComponentInformationServerResult\022`\n\006r" - "esult\030\001 \001(\0162P.mavsdk.rpc.component_infor" - "mation_server.ComponentInformationServer" - "Result.Result\022\022\n\nresult_str\030\002 \001(\t\"\317\001\n\006Re" - "sult\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCE" - "SS\020\001\022\032\n\026RESULT_DUPLICATE_PARAM\020\002\022$\n RESU" - "LT_INVALID_PARAM_START_VALUE\020\003\022&\n\"RESULT" - "_INVALID_PARAM_DEFAULT_VALUE\020\004\022\035\n\031RESULT" - "_INVALID_PARAM_NAME\020\005\022\024\n\020RESULT_NO_SYSTE" - "M\020\0062\350\002\n!ComponentInformationServerServic" - "e\022\240\001\n\021ProvideFloatParam\022A.mavsdk.rpc.com" - "ponent_information_server.ProvideFloatPa" - "ramRequest\032B.mavsdk.rpc.component_inform" - "ation_server.ProvideFloatParamResponse\"\004" - "\200\265\030\001\022\237\001\n\023SubscribeFloatParam\022C.mavsdk.rp" - "c.component_information_server.Subscribe" - "FloatParamRequest\032;.mavsdk.rpc.component" - "_information_server.FloatParamResponse\"\004" - "\200\265\030\0000\001BI\n&io.mavsdk.component_informatio" - "n_serverB\037ComponentInformationServerProt" - "ob\006proto3" -}; -static const ::_pbi::DescriptorTable* const descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_deps[1] = - { - &::descriptor_table_mavsdk_5foptions_2eproto, -}; -static ::absl::once_flag descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once; -const ::_pbi::DescriptorTable descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto = { - false, - false, - 1569, - descriptor_table_protodef_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto, - "component_information_server/component_information_server.proto", - &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, - descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_deps, - 1, - 7, - schemas, - file_default_instances, - TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto::offsets, - file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto, - file_level_enum_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto, - file_level_service_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_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_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter() { - return &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -} -// Force running AddDescriptors() at dynamic initialization time. -PROTOBUF_ATTRIBUTE_INIT_PRIORITY2 -static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto(&descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto); -namespace mavsdk { -namespace rpc { -namespace component_information_server { -const ::google::protobuf::EnumDescriptor* ComponentInformationServerResult_Result_descriptor() { - ::google::protobuf::internal::AssignDescriptors(&descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto); - return file_level_enum_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[0]; -} -PROTOBUF_CONSTINIT const uint32_t ComponentInformationServerResult_Result_internal_data_[] = { - 458752u, 0u, }; -bool ComponentInformationServerResult_Result_IsValid(int value) { - return 0 <= value && value <= 6; -} -#if (__cplusplus < 201703) && \ - (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) - -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_UNKNOWN; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_SUCCESS; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_DUPLICATE_PARAM; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_INVALID_PARAM_START_VALUE; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_INVALID_PARAM_DEFAULT_VALUE; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_INVALID_PARAM_NAME; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_NO_SYSTEM; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::Result_MIN; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::Result_MAX; -constexpr int ComponentInformationServerResult::Result_ARRAYSIZE; - -#endif // (__cplusplus < 201703) && - // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) -// =================================================================== - -class FloatParam::_Internal { - public: -}; - -FloatParam::FloatParam(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information_server.FloatParam) -} -inline PROTOBUF_NDEBUG_INLINE FloatParam::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : name_(arena, from.name_), - short_description_(arena, from.short_description_), - long_description_(arena, from.long_description_), - unit_(arena, from.unit_), - _cached_size_{0} {} - -FloatParam::FloatParam( - ::google::protobuf::Arena* arena, - const FloatParam& from) - : ::google::protobuf::Message(arena) { - FloatParam* 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_, decimal_places_), - reinterpret_cast(&from._impl_) + - offsetof(Impl_, decimal_places_), - offsetof(Impl_, max_value_) - - offsetof(Impl_, decimal_places_) + - sizeof(Impl_::max_value_)); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.FloatParam) -} -inline PROTOBUF_NDEBUG_INLINE FloatParam::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : name_(arena), - short_description_(arena), - long_description_(arena), - unit_(arena), - _cached_size_{0} {} - -inline void FloatParam::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, decimal_places_), - 0, - offsetof(Impl_, max_value_) - - offsetof(Impl_, decimal_places_) + - sizeof(Impl_::max_value_)); -} -FloatParam::~FloatParam() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.FloatParam) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void FloatParam::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.name_.Destroy(); - _impl_.short_description_.Destroy(); - _impl_.long_description_.Destroy(); - _impl_.unit_.Destroy(); - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void FloatParam::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.FloatParam) - 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_.short_description_.ClearToEmpty(); - _impl_.long_description_.ClearToEmpty(); - _impl_.unit_.ClearToEmpty(); - ::memset(&_impl_.decimal_places_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.max_value_) - - reinterpret_cast(&_impl_.decimal_places_)) + sizeof(_impl_.max_value_)); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* FloatParam::_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<4, 9, 0, 108, 2> FloatParam::_table_ = { - { - 0, // no _has_bits_ - 0, // no _extensions_ - 9, 120, // max_field_number, fast_idx_mask - offsetof(decltype(_table_), field_lookup_table), - 4294966784, // skipmap - offsetof(decltype(_table_), field_entries), - 9, // num_field_entries - 0, // num_aux_entries - offsetof(decltype(_table_), field_names), // no aux_entries - &_FloatParam_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - {::_pbi::TcParser::MiniParse, {}}, - // string name = 1; - {::_pbi::TcParser::FastUS1, - {10, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.name_)}}, - // string short_description = 2; - {::_pbi::TcParser::FastUS1, - {18, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.short_description_)}}, - // string long_description = 3; - {::_pbi::TcParser::FastUS1, - {26, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.long_description_)}}, - // string unit = 4; - {::_pbi::TcParser::FastUS1, - {34, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.unit_)}}, - // int32 decimal_places = 5; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FloatParam, _impl_.decimal_places_), 63>(), - {40, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.decimal_places_)}}, - // float start_value = 6; - {::_pbi::TcParser::FastF32S1, - {53, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.start_value_)}}, - // float default_value = 7; - {::_pbi::TcParser::FastF32S1, - {61, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.default_value_)}}, - // float min_value = 8; - {::_pbi::TcParser::FastF32S1, - {69, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.min_value_)}}, - // float max_value = 9; - {::_pbi::TcParser::FastF32S1, - {77, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.max_value_)}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - {::_pbi::TcParser::MiniParse, {}}, - }}, {{ - 65535, 65535 - }}, {{ - // string name = 1; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.name_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // string short_description = 2; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.short_description_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // string long_description = 3; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.long_description_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // string unit = 4; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.unit_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // int32 decimal_places = 5; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.decimal_places_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, - // float start_value = 6; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.start_value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float default_value = 7; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.default_value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float min_value = 8; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.min_value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float max_value = 9; - {PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.max_value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - }}, - // no aux_entries - {{ - "\62\4\21\20\4\0\0\0\0\0\0\0\0\0\0\0" - "mavsdk.rpc.component_information_server.FloatParam" - "name" - "short_description" - "long_description" - "unit" - }}, -}; - -::uint8_t* FloatParam::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.FloatParam) - ::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.component_information_server.FloatParam.name"); - target = stream->WriteStringMaybeAliased(1, _s, target); - } - - // string short_description = 2; - if (!this->_internal_short_description().empty()) { - const std::string& _s = this->_internal_short_description(); - ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_information_server.FloatParam.short_description"); - target = stream->WriteStringMaybeAliased(2, _s, target); - } - - // string long_description = 3; - if (!this->_internal_long_description().empty()) { - const std::string& _s = this->_internal_long_description(); - ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_information_server.FloatParam.long_description"); - target = stream->WriteStringMaybeAliased(3, _s, target); - } - - // string unit = 4; - if (!this->_internal_unit().empty()) { - const std::string& _s = this->_internal_unit(); - ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.component_information_server.FloatParam.unit"); - target = stream->WriteStringMaybeAliased(4, _s, target); - } - - // int32 decimal_places = 5; - if (this->_internal_decimal_places() != 0) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteInt32ToArrayWithField<5>( - stream, this->_internal_decimal_places(), target); - } - - // float start_value = 6; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_start_value = this->_internal_start_value(); - ::uint32_t raw_start_value; - memcpy(&raw_start_value, &tmp_start_value, sizeof(tmp_start_value)); - if (raw_start_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 6, this->_internal_start_value(), target); - } - - // float default_value = 7; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_default_value = this->_internal_default_value(); - ::uint32_t raw_default_value; - memcpy(&raw_default_value, &tmp_default_value, sizeof(tmp_default_value)); - if (raw_default_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 7, this->_internal_default_value(), target); - } - - // float min_value = 8; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_min_value = this->_internal_min_value(); - ::uint32_t raw_min_value; - memcpy(&raw_min_value, &tmp_min_value, sizeof(tmp_min_value)); - if (raw_min_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 8, this->_internal_min_value(), target); - } - - // float max_value = 9; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_max_value = this->_internal_max_value(); - ::uint32_t raw_max_value; - memcpy(&raw_max_value, &tmp_max_value, sizeof(tmp_max_value)); - if (raw_max_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 9, this->_internal_max_value(), 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.component_information_server.FloatParam) - return target; -} - -::size_t FloatParam::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.FloatParam) - ::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 short_description = 2; - if (!this->_internal_short_description().empty()) { - total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( - this->_internal_short_description()); - } - - // string long_description = 3; - if (!this->_internal_long_description().empty()) { - total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( - this->_internal_long_description()); - } - - // string unit = 4; - if (!this->_internal_unit().empty()) { - total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( - this->_internal_unit()); - } - - // int32 decimal_places = 5; - if (this->_internal_decimal_places() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_decimal_places()); - } - - // float start_value = 6; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_start_value = this->_internal_start_value(); - ::uint32_t raw_start_value; - memcpy(&raw_start_value, &tmp_start_value, sizeof(tmp_start_value)); - if (raw_start_value != 0) { - total_size += 5; - } - - // float default_value = 7; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_default_value = this->_internal_default_value(); - ::uint32_t raw_default_value; - memcpy(&raw_default_value, &tmp_default_value, sizeof(tmp_default_value)); - if (raw_default_value != 0) { - total_size += 5; - } - - // float min_value = 8; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_min_value = this->_internal_min_value(); - ::uint32_t raw_min_value; - memcpy(&raw_min_value, &tmp_min_value, sizeof(tmp_min_value)); - if (raw_min_value != 0) { - total_size += 5; - } - - // float max_value = 9; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_max_value = this->_internal_max_value(); - ::uint32_t raw_max_value; - memcpy(&raw_max_value, &tmp_max_value, sizeof(tmp_max_value)); - if (raw_max_value != 0) { - total_size += 5; - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData FloatParam::_class_data_ = { - FloatParam::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* FloatParam::GetClassData() const { - return &_class_data_; -} - -void FloatParam::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.component_information_server.FloatParam) - 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_short_description().empty()) { - _this->_internal_set_short_description(from._internal_short_description()); - } - if (!from._internal_long_description().empty()) { - _this->_internal_set_long_description(from._internal_long_description()); - } - if (!from._internal_unit().empty()) { - _this->_internal_set_unit(from._internal_unit()); - } - if (from._internal_decimal_places() != 0) { - _this->_internal_set_decimal_places(from._internal_decimal_places()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_start_value = from._internal_start_value(); - ::uint32_t raw_start_value; - memcpy(&raw_start_value, &tmp_start_value, sizeof(tmp_start_value)); - if (raw_start_value != 0) { - _this->_internal_set_start_value(from._internal_start_value()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_default_value = from._internal_default_value(); - ::uint32_t raw_default_value; - memcpy(&raw_default_value, &tmp_default_value, sizeof(tmp_default_value)); - if (raw_default_value != 0) { - _this->_internal_set_default_value(from._internal_default_value()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_min_value = from._internal_min_value(); - ::uint32_t raw_min_value; - memcpy(&raw_min_value, &tmp_min_value, sizeof(tmp_min_value)); - if (raw_min_value != 0) { - _this->_internal_set_min_value(from._internal_min_value()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_max_value = from._internal_max_value(); - ::uint32_t raw_max_value; - memcpy(&raw_max_value, &tmp_max_value, sizeof(tmp_max_value)); - if (raw_max_value != 0) { - _this->_internal_set_max_value(from._internal_max_value()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void FloatParam::CopyFrom(const FloatParam& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.FloatParam) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool FloatParam::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* FloatParam::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void FloatParam::InternalSwap(FloatParam* 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_.short_description_, &other->_impl_.short_description_, arena); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.long_description_, &other->_impl_.long_description_, arena); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.unit_, &other->_impl_.unit_, arena); - ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.max_value_) - + sizeof(FloatParam::_impl_.max_value_) - - PROTOBUF_FIELD_OFFSET(FloatParam, _impl_.decimal_places_)>( - reinterpret_cast(&_impl_.decimal_places_), - reinterpret_cast(&other->_impl_.decimal_places_)); -} - -::google::protobuf::Metadata FloatParam::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, - file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[0]); -} -// =================================================================== - -class ProvideFloatParamRequest::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ProvideFloatParamRequest, _impl_._has_bits_); - static const ::mavsdk::rpc::component_information_server::FloatParam& param(const ProvideFloatParamRequest* msg); - static void set_has_param(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::component_information_server::FloatParam& ProvideFloatParamRequest::_Internal::param(const ProvideFloatParamRequest* msg) { - return *msg->_impl_.param_; -} -ProvideFloatParamRequest::ProvideFloatParamRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) -} -inline PROTOBUF_NDEBUG_INLINE ProvideFloatParamRequest::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -ProvideFloatParamRequest::ProvideFloatParamRequest( - ::google::protobuf::Arena* arena, - const ProvideFloatParamRequest& from) - : ::google::protobuf::Message(arena) { - ProvideFloatParamRequest* 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_.param_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::component_information_server::FloatParam>(arena, *from._impl_.param_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) -} -inline PROTOBUF_NDEBUG_INLINE ProvideFloatParamRequest::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void ProvideFloatParamRequest::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.param_ = {}; -} -ProvideFloatParamRequest::~ProvideFloatParamRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void ProvideFloatParamRequest::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.param_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void ProvideFloatParamRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) - 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_.param_ != nullptr); - _impl_.param_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* ProvideFloatParamRequest::_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> ProvideFloatParamRequest::_table_ = { - { - PROTOBUF_FIELD_OFFSET(ProvideFloatParamRequest, _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), - &_ProvideFloatParamRequest_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.component_information_server.FloatParam param = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ProvideFloatParamRequest, _impl_.param_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.component_information_server.FloatParam param = 1; - {PROTOBUF_FIELD_OFFSET(ProvideFloatParamRequest, _impl_.param_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_information_server::FloatParam>()}, - }}, {{ - }}, -}; - -::uint8_t* ProvideFloatParamRequest::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.component_information_server.FloatParam param = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::param(this), - _Internal::param(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.component_information_server.ProvideFloatParamRequest) - return target; -} - -::size_t ProvideFloatParamRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) - ::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.component_information_server.FloatParam param = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.param_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData ProvideFloatParamRequest::_class_data_ = { - ProvideFloatParamRequest::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* ProvideFloatParamRequest::GetClassData() const { - return &_class_data_; -} - -void ProvideFloatParamRequest::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.component_information_server.ProvideFloatParamRequest) - 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_param()->::mavsdk::rpc::component_information_server::FloatParam::MergeFrom( - from._internal_param()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void ProvideFloatParamRequest::CopyFrom(const ProvideFloatParamRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool ProvideFloatParamRequest::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* ProvideFloatParamRequest::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void ProvideFloatParamRequest::InternalSwap(ProvideFloatParamRequest* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.param_, other->_impl_.param_); -} - -::google::protobuf::Metadata ProvideFloatParamRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, - file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[1]); -} -// =================================================================== - -class ProvideFloatParamResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ProvideFloatParamResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& component_information_server_result(const ProvideFloatParamResponse* msg); - static void set_has_component_information_server_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& ProvideFloatParamResponse::_Internal::component_information_server_result(const ProvideFloatParamResponse* msg) { - return *msg->_impl_.component_information_server_result_; -} -ProvideFloatParamResponse::ProvideFloatParamResponse(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) -} -inline PROTOBUF_NDEBUG_INLINE ProvideFloatParamResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -ProvideFloatParamResponse::ProvideFloatParamResponse( - ::google::protobuf::Arena* arena, - const ProvideFloatParamResponse& from) - : ::google::protobuf::Message(arena) { - ProvideFloatParamResponse* 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_.component_information_server_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::component_information_server::ComponentInformationServerResult>(arena, *from._impl_.component_information_server_result_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) -} -inline PROTOBUF_NDEBUG_INLINE ProvideFloatParamResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void ProvideFloatParamResponse::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.component_information_server_result_ = {}; -} -ProvideFloatParamResponse::~ProvideFloatParamResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void ProvideFloatParamResponse::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.component_information_server_result_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void ProvideFloatParamResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) - 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_.component_information_server_result_ != nullptr); - _impl_.component_information_server_result_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* ProvideFloatParamResponse::_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> ProvideFloatParamResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(ProvideFloatParamResponse, _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), - &_ProvideFloatParamResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.component_information_server.ComponentInformationServerResult component_information_server_result = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ProvideFloatParamResponse, _impl_.component_information_server_result_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.component_information_server.ComponentInformationServerResult component_information_server_result = 1; - {PROTOBUF_FIELD_OFFSET(ProvideFloatParamResponse, _impl_.component_information_server_result_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_information_server::ComponentInformationServerResult>()}, - }}, {{ - }}, -}; - -::uint8_t* ProvideFloatParamResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.component_information_server.ComponentInformationServerResult component_information_server_result = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::component_information_server_result(this), - _Internal::component_information_server_result(this).GetCachedSize(), target, stream); - } - - if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { - target = - ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( - _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); - } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) - return target; -} - -::size_t ProvideFloatParamResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) - ::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.component_information_server.ComponentInformationServerResult component_information_server_result = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.component_information_server_result_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData ProvideFloatParamResponse::_class_data_ = { - ProvideFloatParamResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* ProvideFloatParamResponse::GetClassData() const { - return &_class_data_; -} - -void ProvideFloatParamResponse::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.component_information_server.ProvideFloatParamResponse) - 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_component_information_server_result()->::mavsdk::rpc::component_information_server::ComponentInformationServerResult::MergeFrom( - from._internal_component_information_server_result()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void ProvideFloatParamResponse::CopyFrom(const ProvideFloatParamResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool ProvideFloatParamResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* ProvideFloatParamResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void ProvideFloatParamResponse::InternalSwap(ProvideFloatParamResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.component_information_server_result_, other->_impl_.component_information_server_result_); -} - -::google::protobuf::Metadata ProvideFloatParamResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, - file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[2]); -} -// =================================================================== - -class FloatParamUpdate::_Internal { - public: -}; - -FloatParamUpdate::FloatParamUpdate(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information_server.FloatParamUpdate) -} -inline PROTOBUF_NDEBUG_INLINE FloatParamUpdate::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : name_(arena, from.name_), - _cached_size_{0} {} - -FloatParamUpdate::FloatParamUpdate( - ::google::protobuf::Arena* arena, - const FloatParamUpdate& from) - : ::google::protobuf::Message(arena) { - FloatParamUpdate* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - _impl_.value_ = from._impl_.value_; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.FloatParamUpdate) -} -inline PROTOBUF_NDEBUG_INLINE FloatParamUpdate::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : name_(arena), - _cached_size_{0} {} - -inline void FloatParamUpdate::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.value_ = {}; -} -FloatParamUpdate::~FloatParamUpdate() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.FloatParamUpdate) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void FloatParamUpdate::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.name_.Destroy(); - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void FloatParamUpdate::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.FloatParamUpdate) - 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_.value_ = 0; - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* FloatParamUpdate::_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, 69, 2> FloatParamUpdate::_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 - &_FloatParamUpdate_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // float value = 2; - {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParamUpdate, _impl_.value_)}}, - // string name = 1; - {::_pbi::TcParser::FastUS1, - {10, 63, 0, PROTOBUF_FIELD_OFFSET(FloatParamUpdate, _impl_.name_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // string name = 1; - {PROTOBUF_FIELD_OFFSET(FloatParamUpdate, _impl_.name_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // float value = 2; - {PROTOBUF_FIELD_OFFSET(FloatParamUpdate, _impl_.value_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - }}, - // no aux_entries - {{ - "\70\4\0\0\0\0\0\0" - "mavsdk.rpc.component_information_server.FloatParamUpdate" - "name" - }}, -}; - -::uint8_t* FloatParamUpdate::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.FloatParamUpdate) - ::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.component_information_server.FloatParamUpdate.name"); - target = stream->WriteStringMaybeAliased(1, _s, target); - } - - // float value = 2; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_value = this->_internal_value(); - ::uint32_t raw_value; - memcpy(&raw_value, &tmp_value, sizeof(tmp_value)); - if (raw_value != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_value(), 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.component_information_server.FloatParamUpdate) - return target; -} - -::size_t FloatParamUpdate::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.FloatParamUpdate) - ::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()); - } - - // float value = 2; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_value = this->_internal_value(); - ::uint32_t raw_value; - memcpy(&raw_value, &tmp_value, sizeof(tmp_value)); - if (raw_value != 0) { - total_size += 5; - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData FloatParamUpdate::_class_data_ = { - FloatParamUpdate::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* FloatParamUpdate::GetClassData() const { - return &_class_data_; -} - -void FloatParamUpdate::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.component_information_server.FloatParamUpdate) - 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()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_value = from._internal_value(); - ::uint32_t raw_value; - memcpy(&raw_value, &tmp_value, sizeof(tmp_value)); - if (raw_value != 0) { - _this->_internal_set_value(from._internal_value()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void FloatParamUpdate::CopyFrom(const FloatParamUpdate& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.FloatParamUpdate) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool FloatParamUpdate::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* FloatParamUpdate::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void FloatParamUpdate::InternalSwap(FloatParamUpdate* 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); - swap(_impl_.value_, other->_impl_.value_); -} - -::google::protobuf::Metadata FloatParamUpdate::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, - file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[3]); -} -// =================================================================== - -class SubscribeFloatParamRequest::_Internal { - public: -}; - -SubscribeFloatParamRequest::SubscribeFloatParamRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information_server.SubscribeFloatParamRequest) -} -SubscribeFloatParamRequest::SubscribeFloatParamRequest( - ::google::protobuf::Arena* arena, - const SubscribeFloatParamRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeFloatParamRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.SubscribeFloatParamRequest) -} - - - - - - - - - -::google::protobuf::Metadata SubscribeFloatParamRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, - file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[4]); -} -// =================================================================== - -class FloatParamResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(FloatParamResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::component_information_server::FloatParamUpdate& param_update(const FloatParamResponse* msg); - static void set_has_param_update(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::component_information_server::FloatParamUpdate& FloatParamResponse::_Internal::param_update(const FloatParamResponse* msg) { - return *msg->_impl_.param_update_; -} -FloatParamResponse::FloatParamResponse(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information_server.FloatParamResponse) -} -inline PROTOBUF_NDEBUG_INLINE FloatParamResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -FloatParamResponse::FloatParamResponse( - ::google::protobuf::Arena* arena, - const FloatParamResponse& from) - : ::google::protobuf::Message(arena) { - FloatParamResponse* 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_.param_update_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::component_information_server::FloatParamUpdate>(arena, *from._impl_.param_update_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.FloatParamResponse) -} -inline PROTOBUF_NDEBUG_INLINE FloatParamResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void FloatParamResponse::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.param_update_ = {}; -} -FloatParamResponse::~FloatParamResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.FloatParamResponse) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void FloatParamResponse::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.param_update_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void FloatParamResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.FloatParamResponse) - 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_.param_update_ != nullptr); - _impl_.param_update_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* FloatParamResponse::_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> FloatParamResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(FloatParamResponse, _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), - &_FloatParamResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.component_information_server.FloatParamUpdate param_update = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(FloatParamResponse, _impl_.param_update_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.component_information_server.FloatParamUpdate param_update = 1; - {PROTOBUF_FIELD_OFFSET(FloatParamResponse, _impl_.param_update_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::component_information_server::FloatParamUpdate>()}, - }}, {{ - }}, -}; - -::uint8_t* FloatParamResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.FloatParamResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.component_information_server.FloatParamUpdate param_update = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::param_update(this), - _Internal::param_update(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.component_information_server.FloatParamResponse) - return target; -} - -::size_t FloatParamResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.FloatParamResponse) - ::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.component_information_server.FloatParamUpdate param_update = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.param_update_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData FloatParamResponse::_class_data_ = { - FloatParamResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* FloatParamResponse::GetClassData() const { - return &_class_data_; -} - -void FloatParamResponse::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.component_information_server.FloatParamResponse) - 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_param_update()->::mavsdk::rpc::component_information_server::FloatParamUpdate::MergeFrom( - from._internal_param_update()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void FloatParamResponse::CopyFrom(const FloatParamResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.FloatParamResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool FloatParamResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* FloatParamResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void FloatParamResponse::InternalSwap(FloatParamResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.param_update_, other->_impl_.param_update_); -} - -::google::protobuf::Metadata FloatParamResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, - file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[5]); -} -// =================================================================== - -class ComponentInformationServerResult::_Internal { - public: -}; - -ComponentInformationServerResult::ComponentInformationServerResult(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_information_server.ComponentInformationServerResult) -} -inline PROTOBUF_NDEBUG_INLINE ComponentInformationServerResult::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : result_str_(arena, from.result_str_), - _cached_size_{0} {} - -ComponentInformationServerResult::ComponentInformationServerResult( - ::google::protobuf::Arena* arena, - const ComponentInformationServerResult& from) - : ::google::protobuf::Message(arena) { - ComponentInformationServerResult* 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.component_information_server.ComponentInformationServerResult) -} -inline PROTOBUF_NDEBUG_INLINE ComponentInformationServerResult::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : result_str_(arena), - _cached_size_{0} {} - -inline void ComponentInformationServerResult::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.result_ = {}; -} -ComponentInformationServerResult::~ComponentInformationServerResult() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.ComponentInformationServerResult) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void ComponentInformationServerResult::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.result_str_.Destroy(); - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void ComponentInformationServerResult::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) - 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* ComponentInformationServerResult::_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, 91, 2> ComponentInformationServerResult::_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 - &_ComponentInformationServerResult_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // string result_str = 2; - {::_pbi::TcParser::FastUS1, - {18, 63, 0, PROTOBUF_FIELD_OFFSET(ComponentInformationServerResult, _impl_.result_str_)}}, - // .mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result result = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ComponentInformationServerResult, _impl_.result_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(ComponentInformationServerResult, _impl_.result_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result result = 1; - {PROTOBUF_FIELD_OFFSET(ComponentInformationServerResult, _impl_.result_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - // string result_str = 2; - {PROTOBUF_FIELD_OFFSET(ComponentInformationServerResult, _impl_.result_str_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - }}, - // no aux_entries - {{ - "\110\0\12\0\0\0\0\0" - "mavsdk.rpc.component_information_server.ComponentInformationServerResult" - "result_str" - }}, -}; - -::uint8_t* ComponentInformationServerResult::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - // .mavsdk.rpc.component_information_server.ComponentInformationServerResult.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.component_information_server.ComponentInformationServerResult.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.component_information_server.ComponentInformationServerResult) - return target; -} - -::size_t ComponentInformationServerResult::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) - ::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.component_information_server.ComponentInformationServerResult.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 ComponentInformationServerResult::_class_data_ = { - ComponentInformationServerResult::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* ComponentInformationServerResult::GetClassData() const { - return &_class_data_; -} - -void ComponentInformationServerResult::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.component_information_server.ComponentInformationServerResult) - 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 ComponentInformationServerResult::CopyFrom(const ComponentInformationServerResult& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool ComponentInformationServerResult::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* ComponentInformationServerResult::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void ComponentInformationServerResult::InternalSwap(ComponentInformationServerResult* 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 ComponentInformationServerResult::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, - file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[6]); -} -// @@protoc_insertion_point(namespace_scope) -} // namespace component_information_server -} // 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/component_information_server/component_information_server.pb.h b/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.h deleted file mode 100644 index c7089b2c22..0000000000 --- a/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.h +++ /dev/null @@ -1,2359 +0,0 @@ -// Generated by the protocol buffer compiler. DO NOT EDIT! -// source: component_information_server/component_information_server.proto -// Protobuf C++ Version: 4.25.1 - -#ifndef GOOGLE_PROTOBUF_INCLUDED_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_2epb_2eh -#define GOOGLE_PROTOBUF_INCLUDED_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_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_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_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_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto { - static const ::uint32_t offsets[]; -}; -extern const ::google::protobuf::internal::DescriptorTable - descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -namespace mavsdk { -namespace rpc { -namespace component_information_server { -class ComponentInformationServerResult; -struct ComponentInformationServerResultDefaultTypeInternal; -extern ComponentInformationServerResultDefaultTypeInternal _ComponentInformationServerResult_default_instance_; -class FloatParam; -struct FloatParamDefaultTypeInternal; -extern FloatParamDefaultTypeInternal _FloatParam_default_instance_; -class FloatParamResponse; -struct FloatParamResponseDefaultTypeInternal; -extern FloatParamResponseDefaultTypeInternal _FloatParamResponse_default_instance_; -class FloatParamUpdate; -struct FloatParamUpdateDefaultTypeInternal; -extern FloatParamUpdateDefaultTypeInternal _FloatParamUpdate_default_instance_; -class ProvideFloatParamRequest; -struct ProvideFloatParamRequestDefaultTypeInternal; -extern ProvideFloatParamRequestDefaultTypeInternal _ProvideFloatParamRequest_default_instance_; -class ProvideFloatParamResponse; -struct ProvideFloatParamResponseDefaultTypeInternal; -extern ProvideFloatParamResponseDefaultTypeInternal _ProvideFloatParamResponse_default_instance_; -class SubscribeFloatParamRequest; -struct SubscribeFloatParamRequestDefaultTypeInternal; -extern SubscribeFloatParamRequestDefaultTypeInternal _SubscribeFloatParamRequest_default_instance_; -} // namespace component_information_server -} // namespace rpc -} // namespace mavsdk -namespace google { -namespace protobuf { -} // namespace protobuf -} // namespace google - -namespace mavsdk { -namespace rpc { -namespace component_information_server { -enum ComponentInformationServerResult_Result : int { - ComponentInformationServerResult_Result_RESULT_UNKNOWN = 0, - ComponentInformationServerResult_Result_RESULT_SUCCESS = 1, - ComponentInformationServerResult_Result_RESULT_DUPLICATE_PARAM = 2, - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_START_VALUE = 3, - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_DEFAULT_VALUE = 4, - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_NAME = 5, - ComponentInformationServerResult_Result_RESULT_NO_SYSTEM = 6, - ComponentInformationServerResult_Result_ComponentInformationServerResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = - std::numeric_limits<::int32_t>::min(), - ComponentInformationServerResult_Result_ComponentInformationServerResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = - std::numeric_limits<::int32_t>::max(), -}; - -bool ComponentInformationServerResult_Result_IsValid(int value); -extern const uint32_t ComponentInformationServerResult_Result_internal_data_[]; -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult_Result_Result_MIN = static_cast(0); -constexpr ComponentInformationServerResult_Result ComponentInformationServerResult_Result_Result_MAX = static_cast(6); -constexpr int ComponentInformationServerResult_Result_Result_ARRAYSIZE = 6 + 1; -const ::google::protobuf::EnumDescriptor* -ComponentInformationServerResult_Result_descriptor(); -template -const std::string& ComponentInformationServerResult_Result_Name(T value) { - static_assert(std::is_same::value || - std::is_integral::value, - "Incorrect type passed to Result_Name()."); - return ComponentInformationServerResult_Result_Name(static_cast(value)); -} -template <> -inline const std::string& ComponentInformationServerResult_Result_Name(ComponentInformationServerResult_Result value) { - return ::google::protobuf::internal::NameOfDenseEnum( - static_cast(value)); -} -inline bool ComponentInformationServerResult_Result_Parse(absl::string_view name, ComponentInformationServerResult_Result* value) { - return ::google::protobuf::internal::ParseNamedEnum( - ComponentInformationServerResult_Result_descriptor(), name, value); -} - -// =================================================================== - - -// ------------------------------------------------------------------- - -class SubscribeFloatParamRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.SubscribeFloatParamRequest) */ { - public: - inline SubscribeFloatParamRequest() : SubscribeFloatParamRequest(nullptr) {} - template - explicit PROTOBUF_CONSTEXPR SubscribeFloatParamRequest(::google::protobuf::internal::ConstantInitialized); - - inline SubscribeFloatParamRequest(const SubscribeFloatParamRequest& from) - : SubscribeFloatParamRequest(nullptr, from) {} - SubscribeFloatParamRequest(SubscribeFloatParamRequest&& from) noexcept - : SubscribeFloatParamRequest() { - *this = ::std::move(from); - } - - inline SubscribeFloatParamRequest& operator=(const SubscribeFloatParamRequest& from) { - CopyFrom(from); - return *this; - } - inline SubscribeFloatParamRequest& operator=(SubscribeFloatParamRequest&& 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 SubscribeFloatParamRequest& default_instance() { - return *internal_default_instance(); - } - static inline const SubscribeFloatParamRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeFloatParamRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 4; - - friend void swap(SubscribeFloatParamRequest& a, SubscribeFloatParamRequest& b) { - a.Swap(&b); - } - inline void Swap(SubscribeFloatParamRequest* 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(SubscribeFloatParamRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - SubscribeFloatParamRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeFloatParamRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeFloatParamRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); - } - public: - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information_server.SubscribeFloatParamRequest"; - } - protected: - explicit SubscribeFloatParamRequest(::google::protobuf::Arena* arena); - SubscribeFloatParamRequest(::google::protobuf::Arena* arena, const SubscribeFloatParamRequest& from); - public: - - ::google::protobuf::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.SubscribeFloatParamRequest) - 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_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class FloatParamUpdate final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.FloatParamUpdate) */ { - public: - inline FloatParamUpdate() : FloatParamUpdate(nullptr) {} - ~FloatParamUpdate() override; - template - explicit PROTOBUF_CONSTEXPR FloatParamUpdate(::google::protobuf::internal::ConstantInitialized); - - inline FloatParamUpdate(const FloatParamUpdate& from) - : FloatParamUpdate(nullptr, from) {} - FloatParamUpdate(FloatParamUpdate&& from) noexcept - : FloatParamUpdate() { - *this = ::std::move(from); - } - - inline FloatParamUpdate& operator=(const FloatParamUpdate& from) { - CopyFrom(from); - return *this; - } - inline FloatParamUpdate& operator=(FloatParamUpdate&& 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 FloatParamUpdate& default_instance() { - return *internal_default_instance(); - } - static inline const FloatParamUpdate* internal_default_instance() { - return reinterpret_cast( - &_FloatParamUpdate_default_instance_); - } - static constexpr int kIndexInFileMessages = - 3; - - friend void swap(FloatParamUpdate& a, FloatParamUpdate& b) { - a.Swap(&b); - } - inline void Swap(FloatParamUpdate* 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(FloatParamUpdate* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - FloatParamUpdate* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FloatParamUpdate& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FloatParamUpdate& from) { - FloatParamUpdate::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(FloatParamUpdate* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information_server.FloatParamUpdate"; - } - protected: - explicit FloatParamUpdate(::google::protobuf::Arena* arena); - FloatParamUpdate(::google::protobuf::Arena* arena, const FloatParamUpdate& 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, - kValueFieldNumber = 2, - }; - // 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: - // float value = 2; - void clear_value() ; - float value() const; - void set_value(float value); - - private: - float _internal_value() const; - void _internal_set_value(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParamUpdate) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, - 69, 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_; - float value_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class FloatParam final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.FloatParam) */ { - public: - inline FloatParam() : FloatParam(nullptr) {} - ~FloatParam() override; - template - explicit PROTOBUF_CONSTEXPR FloatParam(::google::protobuf::internal::ConstantInitialized); - - inline FloatParam(const FloatParam& from) - : FloatParam(nullptr, from) {} - FloatParam(FloatParam&& from) noexcept - : FloatParam() { - *this = ::std::move(from); - } - - inline FloatParam& operator=(const FloatParam& from) { - CopyFrom(from); - return *this; - } - inline FloatParam& operator=(FloatParam&& 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 FloatParam& default_instance() { - return *internal_default_instance(); - } - static inline const FloatParam* internal_default_instance() { - return reinterpret_cast( - &_FloatParam_default_instance_); - } - static constexpr int kIndexInFileMessages = - 0; - - friend void swap(FloatParam& a, FloatParam& b) { - a.Swap(&b); - } - inline void Swap(FloatParam* 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(FloatParam* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - FloatParam* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FloatParam& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FloatParam& from) { - FloatParam::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(FloatParam* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information_server.FloatParam"; - } - protected: - explicit FloatParam(::google::protobuf::Arena* arena); - FloatParam(::google::protobuf::Arena* arena, const FloatParam& 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, - kShortDescriptionFieldNumber = 2, - kLongDescriptionFieldNumber = 3, - kUnitFieldNumber = 4, - kDecimalPlacesFieldNumber = 5, - kStartValueFieldNumber = 6, - kDefaultValueFieldNumber = 7, - kMinValueFieldNumber = 8, - kMaxValueFieldNumber = 9, - }; - // 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 short_description = 2; - void clear_short_description() ; - const std::string& short_description() const; - template - void set_short_description(Arg_&& arg, Args_... args); - std::string* mutable_short_description(); - PROTOBUF_NODISCARD std::string* release_short_description(); - void set_allocated_short_description(std::string* value); - - private: - const std::string& _internal_short_description() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_short_description( - const std::string& value); - std::string* _internal_mutable_short_description(); - - public: - // string long_description = 3; - void clear_long_description() ; - const std::string& long_description() const; - template - void set_long_description(Arg_&& arg, Args_... args); - std::string* mutable_long_description(); - PROTOBUF_NODISCARD std::string* release_long_description(); - void set_allocated_long_description(std::string* value); - - private: - const std::string& _internal_long_description() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_long_description( - const std::string& value); - std::string* _internal_mutable_long_description(); - - public: - // string unit = 4; - void clear_unit() ; - const std::string& unit() const; - template - void set_unit(Arg_&& arg, Args_... args); - std::string* mutable_unit(); - PROTOBUF_NODISCARD std::string* release_unit(); - void set_allocated_unit(std::string* value); - - private: - const std::string& _internal_unit() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_unit( - const std::string& value); - std::string* _internal_mutable_unit(); - - public: - // int32 decimal_places = 5; - void clear_decimal_places() ; - ::int32_t decimal_places() const; - void set_decimal_places(::int32_t value); - - private: - ::int32_t _internal_decimal_places() const; - void _internal_set_decimal_places(::int32_t value); - - public: - // float start_value = 6; - void clear_start_value() ; - float start_value() const; - void set_start_value(float value); - - private: - float _internal_start_value() const; - void _internal_set_start_value(float value); - - public: - // float default_value = 7; - void clear_default_value() ; - float default_value() const; - void set_default_value(float value); - - private: - float _internal_default_value() const; - void _internal_set_default_value(float value); - - public: - // float min_value = 8; - void clear_min_value() ; - float min_value() const; - void set_min_value(float value); - - private: - float _internal_min_value() const; - void _internal_set_min_value(float value); - - public: - // float max_value = 9; - void clear_max_value() ; - float max_value() const; - void set_max_value(float value); - - private: - float _internal_max_value() const; - void _internal_set_max_value(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParam) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 4, 9, 0, - 108, 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 short_description_; - ::google::protobuf::internal::ArenaStringPtr long_description_; - ::google::protobuf::internal::ArenaStringPtr unit_; - ::int32_t decimal_places_; - float start_value_; - float default_value_; - float min_value_; - float max_value_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class ComponentInformationServerResult final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.ComponentInformationServerResult) */ { - public: - inline ComponentInformationServerResult() : ComponentInformationServerResult(nullptr) {} - ~ComponentInformationServerResult() override; - template - explicit PROTOBUF_CONSTEXPR ComponentInformationServerResult(::google::protobuf::internal::ConstantInitialized); - - inline ComponentInformationServerResult(const ComponentInformationServerResult& from) - : ComponentInformationServerResult(nullptr, from) {} - ComponentInformationServerResult(ComponentInformationServerResult&& from) noexcept - : ComponentInformationServerResult() { - *this = ::std::move(from); - } - - inline ComponentInformationServerResult& operator=(const ComponentInformationServerResult& from) { - CopyFrom(from); - return *this; - } - inline ComponentInformationServerResult& operator=(ComponentInformationServerResult&& 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 ComponentInformationServerResult& default_instance() { - return *internal_default_instance(); - } - static inline const ComponentInformationServerResult* internal_default_instance() { - return reinterpret_cast( - &_ComponentInformationServerResult_default_instance_); - } - static constexpr int kIndexInFileMessages = - 6; - - friend void swap(ComponentInformationServerResult& a, ComponentInformationServerResult& b) { - a.Swap(&b); - } - inline void Swap(ComponentInformationServerResult* 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(ComponentInformationServerResult* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - ComponentInformationServerResult* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ComponentInformationServerResult& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ComponentInformationServerResult& from) { - ComponentInformationServerResult::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(ComponentInformationServerResult* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information_server.ComponentInformationServerResult"; - } - protected: - explicit ComponentInformationServerResult(::google::protobuf::Arena* arena); - ComponentInformationServerResult(::google::protobuf::Arena* arena, const ComponentInformationServerResult& 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 = ComponentInformationServerResult_Result; - static constexpr Result RESULT_UNKNOWN = ComponentInformationServerResult_Result_RESULT_UNKNOWN; - static constexpr Result RESULT_SUCCESS = ComponentInformationServerResult_Result_RESULT_SUCCESS; - static constexpr Result RESULT_DUPLICATE_PARAM = ComponentInformationServerResult_Result_RESULT_DUPLICATE_PARAM; - static constexpr Result RESULT_INVALID_PARAM_START_VALUE = ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_START_VALUE; - static constexpr Result RESULT_INVALID_PARAM_DEFAULT_VALUE = ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_DEFAULT_VALUE; - static constexpr Result RESULT_INVALID_PARAM_NAME = ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_NAME; - static constexpr Result RESULT_NO_SYSTEM = ComponentInformationServerResult_Result_RESULT_NO_SYSTEM; - static inline bool Result_IsValid(int value) { - return ComponentInformationServerResult_Result_IsValid(value); - } - static constexpr Result Result_MIN = ComponentInformationServerResult_Result_Result_MIN; - static constexpr Result Result_MAX = ComponentInformationServerResult_Result_Result_MAX; - static constexpr int Result_ARRAYSIZE = ComponentInformationServerResult_Result_Result_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* Result_descriptor() { - return ComponentInformationServerResult_Result_descriptor(); - } - template - static inline const std::string& Result_Name(T value) { - return ComponentInformationServerResult_Result_Name(value); - } - static inline bool Result_Parse(absl::string_view name, Result* value) { - return ComponentInformationServerResult_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.component_information_server.ComponentInformationServerResult.Result result = 1; - void clear_result() ; - ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result result() const; - void set_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result value); - - private: - ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result _internal_result() const; - void _internal_set_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ComponentInformationServerResult) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, - 91, 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_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class ProvideFloatParamResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) */ { - public: - inline ProvideFloatParamResponse() : ProvideFloatParamResponse(nullptr) {} - ~ProvideFloatParamResponse() override; - template - explicit PROTOBUF_CONSTEXPR ProvideFloatParamResponse(::google::protobuf::internal::ConstantInitialized); - - inline ProvideFloatParamResponse(const ProvideFloatParamResponse& from) - : ProvideFloatParamResponse(nullptr, from) {} - ProvideFloatParamResponse(ProvideFloatParamResponse&& from) noexcept - : ProvideFloatParamResponse() { - *this = ::std::move(from); - } - - inline ProvideFloatParamResponse& operator=(const ProvideFloatParamResponse& from) { - CopyFrom(from); - return *this; - } - inline ProvideFloatParamResponse& operator=(ProvideFloatParamResponse&& 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 ProvideFloatParamResponse& default_instance() { - return *internal_default_instance(); - } - static inline const ProvideFloatParamResponse* internal_default_instance() { - return reinterpret_cast( - &_ProvideFloatParamResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 2; - - friend void swap(ProvideFloatParamResponse& a, ProvideFloatParamResponse& b) { - a.Swap(&b); - } - inline void Swap(ProvideFloatParamResponse* 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(ProvideFloatParamResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - ProvideFloatParamResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ProvideFloatParamResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ProvideFloatParamResponse& from) { - ProvideFloatParamResponse::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(ProvideFloatParamResponse* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information_server.ProvideFloatParamResponse"; - } - protected: - explicit ProvideFloatParamResponse(::google::protobuf::Arena* arena); - ProvideFloatParamResponse(::google::protobuf::Arena* arena, const ProvideFloatParamResponse& 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 { - kComponentInformationServerResultFieldNumber = 1, - }; - // .mavsdk.rpc.component_information_server.ComponentInformationServerResult component_information_server_result = 1; - bool has_component_information_server_result() const; - void clear_component_information_server_result() ; - const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& component_information_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* release_component_information_server_result(); - ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* mutable_component_information_server_result(); - void set_allocated_component_information_server_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult* value); - void unsafe_arena_set_allocated_component_information_server_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult* value); - ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* unsafe_arena_release_component_information_server_result(); - - private: - const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& _internal_component_information_server_result() const; - ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* _internal_mutable_component_information_server_result(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) - 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::component_information_server::ComponentInformationServerResult* component_information_server_result_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class ProvideFloatParamRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) */ { - public: - inline ProvideFloatParamRequest() : ProvideFloatParamRequest(nullptr) {} - ~ProvideFloatParamRequest() override; - template - explicit PROTOBUF_CONSTEXPR ProvideFloatParamRequest(::google::protobuf::internal::ConstantInitialized); - - inline ProvideFloatParamRequest(const ProvideFloatParamRequest& from) - : ProvideFloatParamRequest(nullptr, from) {} - ProvideFloatParamRequest(ProvideFloatParamRequest&& from) noexcept - : ProvideFloatParamRequest() { - *this = ::std::move(from); - } - - inline ProvideFloatParamRequest& operator=(const ProvideFloatParamRequest& from) { - CopyFrom(from); - return *this; - } - inline ProvideFloatParamRequest& operator=(ProvideFloatParamRequest&& 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 ProvideFloatParamRequest& default_instance() { - return *internal_default_instance(); - } - static inline const ProvideFloatParamRequest* internal_default_instance() { - return reinterpret_cast( - &_ProvideFloatParamRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = - 1; - - friend void swap(ProvideFloatParamRequest& a, ProvideFloatParamRequest& b) { - a.Swap(&b); - } - inline void Swap(ProvideFloatParamRequest* 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(ProvideFloatParamRequest* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - ProvideFloatParamRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ProvideFloatParamRequest& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ProvideFloatParamRequest& from) { - ProvideFloatParamRequest::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(ProvideFloatParamRequest* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information_server.ProvideFloatParamRequest"; - } - protected: - explicit ProvideFloatParamRequest(::google::protobuf::Arena* arena); - ProvideFloatParamRequest(::google::protobuf::Arena* arena, const ProvideFloatParamRequest& 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 { - kParamFieldNumber = 1, - }; - // .mavsdk.rpc.component_information_server.FloatParam param = 1; - bool has_param() const; - void clear_param() ; - const ::mavsdk::rpc::component_information_server::FloatParam& param() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::component_information_server::FloatParam* release_param(); - ::mavsdk::rpc::component_information_server::FloatParam* mutable_param(); - void set_allocated_param(::mavsdk::rpc::component_information_server::FloatParam* value); - void unsafe_arena_set_allocated_param(::mavsdk::rpc::component_information_server::FloatParam* value); - ::mavsdk::rpc::component_information_server::FloatParam* unsafe_arena_release_param(); - - private: - const ::mavsdk::rpc::component_information_server::FloatParam& _internal_param() const; - ::mavsdk::rpc::component_information_server::FloatParam* _internal_mutable_param(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) - 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::component_information_server::FloatParam* param_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class FloatParamResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.FloatParamResponse) */ { - public: - inline FloatParamResponse() : FloatParamResponse(nullptr) {} - ~FloatParamResponse() override; - template - explicit PROTOBUF_CONSTEXPR FloatParamResponse(::google::protobuf::internal::ConstantInitialized); - - inline FloatParamResponse(const FloatParamResponse& from) - : FloatParamResponse(nullptr, from) {} - FloatParamResponse(FloatParamResponse&& from) noexcept - : FloatParamResponse() { - *this = ::std::move(from); - } - - inline FloatParamResponse& operator=(const FloatParamResponse& from) { - CopyFrom(from); - return *this; - } - inline FloatParamResponse& operator=(FloatParamResponse&& 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 FloatParamResponse& default_instance() { - return *internal_default_instance(); - } - static inline const FloatParamResponse* internal_default_instance() { - return reinterpret_cast( - &_FloatParamResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 5; - - friend void swap(FloatParamResponse& a, FloatParamResponse& b) { - a.Swap(&b); - } - inline void Swap(FloatParamResponse* 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(FloatParamResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - FloatParamResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FloatParamResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FloatParamResponse& from) { - FloatParamResponse::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(FloatParamResponse* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.component_information_server.FloatParamResponse"; - } - protected: - explicit FloatParamResponse(::google::protobuf::Arena* arena); - FloatParamResponse(::google::protobuf::Arena* arena, const FloatParamResponse& 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 { - kParamUpdateFieldNumber = 1, - }; - // .mavsdk.rpc.component_information_server.FloatParamUpdate param_update = 1; - bool has_param_update() const; - void clear_param_update() ; - const ::mavsdk::rpc::component_information_server::FloatParamUpdate& param_update() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::component_information_server::FloatParamUpdate* release_param_update(); - ::mavsdk::rpc::component_information_server::FloatParamUpdate* mutable_param_update(); - void set_allocated_param_update(::mavsdk::rpc::component_information_server::FloatParamUpdate* value); - void unsafe_arena_set_allocated_param_update(::mavsdk::rpc::component_information_server::FloatParamUpdate* value); - ::mavsdk::rpc::component_information_server::FloatParamUpdate* unsafe_arena_release_param_update(); - - private: - const ::mavsdk::rpc::component_information_server::FloatParamUpdate& _internal_param_update() const; - ::mavsdk::rpc::component_information_server::FloatParamUpdate* _internal_mutable_param_update(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParamResponse) - 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::component_information_server::FloatParamUpdate* param_update_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; -}; - -// =================================================================== - - - - -// =================================================================== - - -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wstrict-aliasing" -#endif // __GNUC__ -// ------------------------------------------------------------------- - -// FloatParam - -// string name = 1; -inline void FloatParam::clear_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.name_.ClearToEmpty(); -} -inline const std::string& FloatParam::name() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.name) - return _internal_name(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParam::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.component_information_server.FloatParam.name) -} -inline std::string* FloatParam::mutable_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_name(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.FloatParam.name) - return _s; -} -inline const std::string& FloatParam::_internal_name() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.name_.Get(); -} -inline void FloatParam::_internal_set_name(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.name_.Set(value, GetArena()); -} -inline std::string* FloatParam::_internal_mutable_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.name_.Mutable( GetArena()); -} -inline std::string* FloatParam::release_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.FloatParam.name) - return _impl_.name_.Release(); -} -inline void FloatParam::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.component_information_server.FloatParam.name) -} - -// string short_description = 2; -inline void FloatParam::clear_short_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.short_description_.ClearToEmpty(); -} -inline const std::string& FloatParam::short_description() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.short_description) - return _internal_short_description(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParam::set_short_description(Arg_&& arg, - Args_... args) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.short_description_.Set(static_cast(arg), args..., GetArena()); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParam.short_description) -} -inline std::string* FloatParam::mutable_short_description() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_short_description(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.FloatParam.short_description) - return _s; -} -inline const std::string& FloatParam::_internal_short_description() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.short_description_.Get(); -} -inline void FloatParam::_internal_set_short_description(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.short_description_.Set(value, GetArena()); -} -inline std::string* FloatParam::_internal_mutable_short_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.short_description_.Mutable( GetArena()); -} -inline std::string* FloatParam::release_short_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.FloatParam.short_description) - return _impl_.short_description_.Release(); -} -inline void FloatParam::set_allocated_short_description(std::string* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.short_description_.SetAllocated(value, GetArena()); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (_impl_.short_description_.IsDefault()) { - _impl_.short_description_.Set("", GetArena()); - } - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information_server.FloatParam.short_description) -} - -// string long_description = 3; -inline void FloatParam::clear_long_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.long_description_.ClearToEmpty(); -} -inline const std::string& FloatParam::long_description() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.long_description) - return _internal_long_description(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParam::set_long_description(Arg_&& arg, - Args_... args) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.long_description_.Set(static_cast(arg), args..., GetArena()); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParam.long_description) -} -inline std::string* FloatParam::mutable_long_description() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_long_description(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.FloatParam.long_description) - return _s; -} -inline const std::string& FloatParam::_internal_long_description() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.long_description_.Get(); -} -inline void FloatParam::_internal_set_long_description(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.long_description_.Set(value, GetArena()); -} -inline std::string* FloatParam::_internal_mutable_long_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.long_description_.Mutable( GetArena()); -} -inline std::string* FloatParam::release_long_description() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.FloatParam.long_description) - return _impl_.long_description_.Release(); -} -inline void FloatParam::set_allocated_long_description(std::string* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.long_description_.SetAllocated(value, GetArena()); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (_impl_.long_description_.IsDefault()) { - _impl_.long_description_.Set("", GetArena()); - } - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information_server.FloatParam.long_description) -} - -// string unit = 4; -inline void FloatParam::clear_unit() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.unit_.ClearToEmpty(); -} -inline const std::string& FloatParam::unit() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.unit) - return _internal_unit(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParam::set_unit(Arg_&& arg, - Args_... args) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.unit_.Set(static_cast(arg), args..., GetArena()); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParam.unit) -} -inline std::string* FloatParam::mutable_unit() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_unit(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.FloatParam.unit) - return _s; -} -inline const std::string& FloatParam::_internal_unit() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.unit_.Get(); -} -inline void FloatParam::_internal_set_unit(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.unit_.Set(value, GetArena()); -} -inline std::string* FloatParam::_internal_mutable_unit() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.unit_.Mutable( GetArena()); -} -inline std::string* FloatParam::release_unit() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.FloatParam.unit) - return _impl_.unit_.Release(); -} -inline void FloatParam::set_allocated_unit(std::string* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.unit_.SetAllocated(value, GetArena()); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (_impl_.unit_.IsDefault()) { - _impl_.unit_.Set("", GetArena()); - } - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information_server.FloatParam.unit) -} - -// int32 decimal_places = 5; -inline void FloatParam::clear_decimal_places() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.decimal_places_ = 0; -} -inline ::int32_t FloatParam::decimal_places() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.decimal_places) - return _internal_decimal_places(); -} -inline void FloatParam::set_decimal_places(::int32_t value) { - _internal_set_decimal_places(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParam.decimal_places) -} -inline ::int32_t FloatParam::_internal_decimal_places() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.decimal_places_; -} -inline void FloatParam::_internal_set_decimal_places(::int32_t value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.decimal_places_ = value; -} - -// float start_value = 6; -inline void FloatParam::clear_start_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.start_value_ = 0; -} -inline float FloatParam::start_value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.start_value) - return _internal_start_value(); -} -inline void FloatParam::set_start_value(float value) { - _internal_set_start_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParam.start_value) -} -inline float FloatParam::_internal_start_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.start_value_; -} -inline void FloatParam::_internal_set_start_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.start_value_ = value; -} - -// float default_value = 7; -inline void FloatParam::clear_default_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.default_value_ = 0; -} -inline float FloatParam::default_value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.default_value) - return _internal_default_value(); -} -inline void FloatParam::set_default_value(float value) { - _internal_set_default_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParam.default_value) -} -inline float FloatParam::_internal_default_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.default_value_; -} -inline void FloatParam::_internal_set_default_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.default_value_ = value; -} - -// float min_value = 8; -inline void FloatParam::clear_min_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.min_value_ = 0; -} -inline float FloatParam::min_value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.min_value) - return _internal_min_value(); -} -inline void FloatParam::set_min_value(float value) { - _internal_set_min_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParam.min_value) -} -inline float FloatParam::_internal_min_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.min_value_; -} -inline void FloatParam::_internal_set_min_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.min_value_ = value; -} - -// float max_value = 9; -inline void FloatParam::clear_max_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.max_value_ = 0; -} -inline float FloatParam::max_value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParam.max_value) - return _internal_max_value(); -} -inline void FloatParam::set_max_value(float value) { - _internal_set_max_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParam.max_value) -} -inline float FloatParam::_internal_max_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.max_value_; -} -inline void FloatParam::_internal_set_max_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.max_value_ = value; -} - -// ------------------------------------------------------------------- - -// ProvideFloatParamRequest - -// .mavsdk.rpc.component_information_server.FloatParam param = 1; -inline bool ProvideFloatParamRequest::has_param() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.param_ != nullptr); - return value; -} -inline void ProvideFloatParamRequest::clear_param() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.param_ != nullptr) _impl_.param_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::component_information_server::FloatParam& ProvideFloatParamRequest::_internal_param() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::component_information_server::FloatParam* p = _impl_.param_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::component_information_server::_FloatParam_default_instance_); -} -inline const ::mavsdk::rpc::component_information_server::FloatParam& ProvideFloatParamRequest::param() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.ProvideFloatParamRequest.param) - return _internal_param(); -} -inline void ProvideFloatParamRequest::unsafe_arena_set_allocated_param(::mavsdk::rpc::component_information_server::FloatParam* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.param_); - } - _impl_.param_ = reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParam*>(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.component_information_server.ProvideFloatParamRequest.param) -} -inline ::mavsdk::rpc::component_information_server::FloatParam* ProvideFloatParamRequest::release_param() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information_server::FloatParam* released = _impl_.param_; - _impl_.param_ = 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::component_information_server::FloatParam* ProvideFloatParamRequest::unsafe_arena_release_param() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.ProvideFloatParamRequest.param) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information_server::FloatParam* temp = _impl_.param_; - _impl_.param_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::component_information_server::FloatParam* ProvideFloatParamRequest::_internal_mutable_param() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.param_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::component_information_server::FloatParam>(GetArena()); - _impl_.param_ = reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParam*>(p); - } - return _impl_.param_; -} -inline ::mavsdk::rpc::component_information_server::FloatParam* ProvideFloatParamRequest::mutable_param() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::component_information_server::FloatParam* _msg = _internal_mutable_param(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.ProvideFloatParamRequest.param) - return _msg; -} -inline void ProvideFloatParamRequest::set_allocated_param(::mavsdk::rpc::component_information_server::FloatParam* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParam*>(_impl_.param_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParam*>(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_.param_ = reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParam*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information_server.ProvideFloatParamRequest.param) -} - -// ------------------------------------------------------------------- - -// ProvideFloatParamResponse - -// .mavsdk.rpc.component_information_server.ComponentInformationServerResult component_information_server_result = 1; -inline bool ProvideFloatParamResponse::has_component_information_server_result() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.component_information_server_result_ != nullptr); - return value; -} -inline void ProvideFloatParamResponse::clear_component_information_server_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.component_information_server_result_ != nullptr) _impl_.component_information_server_result_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& ProvideFloatParamResponse::_internal_component_information_server_result() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* p = _impl_.component_information_server_result_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::component_information_server::_ComponentInformationServerResult_default_instance_); -} -inline const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& ProvideFloatParamResponse::component_information_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.ProvideFloatParamResponse.component_information_server_result) - return _internal_component_information_server_result(); -} -inline void ProvideFloatParamResponse::unsafe_arena_set_allocated_component_information_server_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.component_information_server_result_); - } - _impl_.component_information_server_result_ = reinterpret_cast<::mavsdk::rpc::component_information_server::ComponentInformationServerResult*>(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.component_information_server.ProvideFloatParamResponse.component_information_server_result) -} -inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* ProvideFloatParamResponse::release_component_information_server_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* released = _impl_.component_information_server_result_; - _impl_.component_information_server_result_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - if (GetArena() == nullptr) { - delete old; - } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArena() != nullptr) { - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return released; -} -inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* ProvideFloatParamResponse::unsafe_arena_release_component_information_server_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.ProvideFloatParamResponse.component_information_server_result) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* temp = _impl_.component_information_server_result_; - _impl_.component_information_server_result_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* ProvideFloatParamResponse::_internal_mutable_component_information_server_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.component_information_server_result_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::component_information_server::ComponentInformationServerResult>(GetArena()); - _impl_.component_information_server_result_ = reinterpret_cast<::mavsdk::rpc::component_information_server::ComponentInformationServerResult*>(p); - } - return _impl_.component_information_server_result_; -} -inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* ProvideFloatParamResponse::mutable_component_information_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* _msg = _internal_mutable_component_information_server_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.ProvideFloatParamResponse.component_information_server_result) - return _msg; -} -inline void ProvideFloatParamResponse::set_allocated_component_information_server_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::component_information_server::ComponentInformationServerResult*>(_impl_.component_information_server_result_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::component_information_server::ComponentInformationServerResult*>(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_.component_information_server_result_ = reinterpret_cast<::mavsdk::rpc::component_information_server::ComponentInformationServerResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information_server.ProvideFloatParamResponse.component_information_server_result) -} - -// ------------------------------------------------------------------- - -// FloatParamUpdate - -// string name = 1; -inline void FloatParamUpdate::clear_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.name_.ClearToEmpty(); -} -inline const std::string& FloatParamUpdate::name() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParamUpdate.name) - return _internal_name(); -} -template -inline PROTOBUF_ALWAYS_INLINE void FloatParamUpdate::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.component_information_server.FloatParamUpdate.name) -} -inline std::string* FloatParamUpdate::mutable_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_name(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.FloatParamUpdate.name) - return _s; -} -inline const std::string& FloatParamUpdate::_internal_name() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.name_.Get(); -} -inline void FloatParamUpdate::_internal_set_name(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.name_.Set(value, GetArena()); -} -inline std::string* FloatParamUpdate::_internal_mutable_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.name_.Mutable( GetArena()); -} -inline std::string* FloatParamUpdate::release_name() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.FloatParamUpdate.name) - return _impl_.name_.Release(); -} -inline void FloatParamUpdate::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.component_information_server.FloatParamUpdate.name) -} - -// float value = 2; -inline void FloatParamUpdate::clear_value() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.value_ = 0; -} -inline float FloatParamUpdate::value() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParamUpdate.value) - return _internal_value(); -} -inline void FloatParamUpdate::set_value(float value) { - _internal_set_value(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.FloatParamUpdate.value) -} -inline float FloatParamUpdate::_internal_value() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.value_; -} -inline void FloatParamUpdate::_internal_set_value(float value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.value_ = value; -} - -// ------------------------------------------------------------------- - -// SubscribeFloatParamRequest - -// ------------------------------------------------------------------- - -// FloatParamResponse - -// .mavsdk.rpc.component_information_server.FloatParamUpdate param_update = 1; -inline bool FloatParamResponse::has_param_update() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.param_update_ != nullptr); - return value; -} -inline void FloatParamResponse::clear_param_update() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.param_update_ != nullptr) _impl_.param_update_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::component_information_server::FloatParamUpdate& FloatParamResponse::_internal_param_update() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::component_information_server::FloatParamUpdate* p = _impl_.param_update_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::component_information_server::_FloatParamUpdate_default_instance_); -} -inline const ::mavsdk::rpc::component_information_server::FloatParamUpdate& FloatParamResponse::param_update() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.FloatParamResponse.param_update) - return _internal_param_update(); -} -inline void FloatParamResponse::unsafe_arena_set_allocated_param_update(::mavsdk::rpc::component_information_server::FloatParamUpdate* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.param_update_); - } - _impl_.param_update_ = reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParamUpdate*>(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.component_information_server.FloatParamResponse.param_update) -} -inline ::mavsdk::rpc::component_information_server::FloatParamUpdate* FloatParamResponse::release_param_update() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information_server::FloatParamUpdate* released = _impl_.param_update_; - _impl_.param_update_ = 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::component_information_server::FloatParamUpdate* FloatParamResponse::unsafe_arena_release_param_update() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.FloatParamResponse.param_update) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::component_information_server::FloatParamUpdate* temp = _impl_.param_update_; - _impl_.param_update_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::component_information_server::FloatParamUpdate* FloatParamResponse::_internal_mutable_param_update() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.param_update_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::component_information_server::FloatParamUpdate>(GetArena()); - _impl_.param_update_ = reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParamUpdate*>(p); - } - return _impl_.param_update_; -} -inline ::mavsdk::rpc::component_information_server::FloatParamUpdate* FloatParamResponse::mutable_param_update() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::component_information_server::FloatParamUpdate* _msg = _internal_mutable_param_update(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.FloatParamResponse.param_update) - return _msg; -} -inline void FloatParamResponse::set_allocated_param_update(::mavsdk::rpc::component_information_server::FloatParamUpdate* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParamUpdate*>(_impl_.param_update_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParamUpdate*>(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_.param_update_ = reinterpret_cast<::mavsdk::rpc::component_information_server::FloatParamUpdate*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information_server.FloatParamResponse.param_update) -} - -// ------------------------------------------------------------------- - -// ComponentInformationServerResult - -// .mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result result = 1; -inline void ComponentInformationServerResult::clear_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.result_ = 0; -} -inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result ComponentInformationServerResult::result() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result) - return _internal_result(); -} -inline void ComponentInformationServerResult::set_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result value) { - _internal_set_result(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result) -} -inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result ComponentInformationServerResult::_internal_result() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return static_cast<::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result>(_impl_.result_); -} -inline void ComponentInformationServerResult::_internal_set_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.result_ = value; -} - -// string result_str = 2; -inline void ComponentInformationServerResult::clear_result_str() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.result_str_.ClearToEmpty(); -} -inline const std::string& ComponentInformationServerResult::result_str() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str) - return _internal_result_str(); -} -template -inline PROTOBUF_ALWAYS_INLINE void ComponentInformationServerResult::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.component_information_server.ComponentInformationServerResult.result_str) -} -inline std::string* ComponentInformationServerResult::mutable_result_str() ABSL_ATTRIBUTE_LIFETIME_BOUND { - std::string* _s = _internal_mutable_result_str(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str) - return _s; -} -inline const std::string& ComponentInformationServerResult::_internal_result_str() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.result_str_.Get(); -} -inline void ComponentInformationServerResult::_internal_set_result_str(const std::string& value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.result_str_.Set(value, GetArena()); -} -inline std::string* ComponentInformationServerResult::_internal_mutable_result_str() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - return _impl_.result_str_.Mutable( GetArena()); -} -inline std::string* ComponentInformationServerResult::release_result_str() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str) - return _impl_.result_str_.Release(); -} -inline void ComponentInformationServerResult::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.component_information_server.ComponentInformationServerResult.result_str) -} - -#ifdef __GNUC__ -#pragma GCC diagnostic pop -#endif // __GNUC__ - -// @@protoc_insertion_point(namespace_scope) -} // namespace component_information_server -} // namespace rpc -} // namespace mavsdk - - -namespace google { -namespace protobuf { - -template <> -struct is_proto_enum<::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result> : std::true_type {}; -template <> -inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result>() { - return ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result_descriptor(); -} - -} // namespace protobuf -} // namespace google - -// @@protoc_insertion_point(global_scope) - -#include "google/protobuf/port_undef.inc" - -#endif // GOOGLE_PROTOBUF_INCLUDED_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_2epb_2eh diff --git a/src/mavsdk_server/src/plugins/component_information/component_information_service_impl.h b/src/mavsdk_server/src/plugins/component_information/component_information_service_impl.h deleted file mode 100644 index cd359e4299..0000000000 --- a/src/mavsdk_server/src/plugins/component_information/component_information_service_impl.h +++ /dev/null @@ -1,272 +0,0 @@ -// 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/component_information/component_information.proto) - -#include "component_information/component_information.grpc.pb.h" -#include "plugins/component_information/component_information.h" - -#include "mavsdk.h" - -#include "lazy_plugin.h" - -#include "log.h" -#include -#include -#include -#include -#include -#include -#include - -namespace mavsdk { -namespace mavsdk_server { - -template< - typename ComponentInformation = ComponentInformation, - typename LazyPlugin = LazyPlugin> - -class ComponentInformationServiceImpl final - : public rpc::component_information::ComponentInformationService::Service { -public: - ComponentInformationServiceImpl(LazyPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) {} - - template - void fillResponseWithResult( - ResponseType* response, mavsdk::ComponentInformation::Result& result) const - { - auto rpc_result = translateToRpcResult(result); - - auto* rpc_component_information_result = - new rpc::component_information::ComponentInformationResult(); - rpc_component_information_result->set_result(rpc_result); - std::stringstream ss; - ss << result; - rpc_component_information_result->set_result_str(ss.str()); - - response->set_allocated_component_information_result(rpc_component_information_result); - } - - static std::unique_ptr - translateToRpcFloatParam(const mavsdk::ComponentInformation::FloatParam& float_param) - { - auto rpc_obj = std::make_unique(); - - rpc_obj->set_name(float_param.name); - - rpc_obj->set_short_description(float_param.short_description); - - rpc_obj->set_long_description(float_param.long_description); - - rpc_obj->set_unit(float_param.unit); - - rpc_obj->set_decimal_places(float_param.decimal_places); - - rpc_obj->set_start_value(float_param.start_value); - - rpc_obj->set_default_value(float_param.default_value); - - rpc_obj->set_min_value(float_param.min_value); - - rpc_obj->set_max_value(float_param.max_value); - - return rpc_obj; - } - - static mavsdk::ComponentInformation::FloatParam - translateFromRpcFloatParam(const rpc::component_information::FloatParam& float_param) - { - mavsdk::ComponentInformation::FloatParam obj; - - obj.name = float_param.name(); - - obj.short_description = float_param.short_description(); - - obj.long_description = float_param.long_description(); - - obj.unit = float_param.unit(); - - obj.decimal_places = float_param.decimal_places(); - - obj.start_value = float_param.start_value(); - - obj.default_value = float_param.default_value(); - - obj.min_value = float_param.min_value(); - - obj.max_value = float_param.max_value(); - - return obj; - } - - static std::unique_ptr - translateToRpcFloatParamUpdate( - const mavsdk::ComponentInformation::FloatParamUpdate& float_param_update) - { - auto rpc_obj = std::make_unique(); - - rpc_obj->set_name(float_param_update.name); - - rpc_obj->set_value(float_param_update.value); - - return rpc_obj; - } - - static mavsdk::ComponentInformation::FloatParamUpdate translateFromRpcFloatParamUpdate( - const rpc::component_information::FloatParamUpdate& float_param_update) - { - mavsdk::ComponentInformation::FloatParamUpdate obj; - - obj.name = float_param_update.name(); - - obj.value = float_param_update.value(); - - return obj; - } - - static rpc::component_information::ComponentInformationResult::Result - translateToRpcResult(const mavsdk::ComponentInformation::Result& result) - { - switch (result) { - default: - LogErr() << "Unknown result enum value: " << static_cast(result); - // FALLTHROUGH - case mavsdk::ComponentInformation::Result::Unknown: - return rpc::component_information::ComponentInformationResult_Result_RESULT_UNKNOWN; - case mavsdk::ComponentInformation::Result::Success: - return rpc::component_information::ComponentInformationResult_Result_RESULT_SUCCESS; - case mavsdk::ComponentInformation::Result::NoSystem: - return rpc::component_information:: - ComponentInformationResult_Result_RESULT_NO_SYSTEM; - } - } - - static mavsdk::ComponentInformation::Result translateFromRpcResult( - const rpc::component_information::ComponentInformationResult::Result result) - { - switch (result) { - default: - LogErr() << "Unknown result enum value: " << static_cast(result); - // FALLTHROUGH - case rpc::component_information::ComponentInformationResult_Result_RESULT_UNKNOWN: - return mavsdk::ComponentInformation::Result::Unknown; - case rpc::component_information::ComponentInformationResult_Result_RESULT_SUCCESS: - return mavsdk::ComponentInformation::Result::Success; - case rpc::component_information::ComponentInformationResult_Result_RESULT_NO_SYSTEM: - return mavsdk::ComponentInformation::Result::NoSystem; - } - } - - grpc::Status AccessFloatParams( - grpc::ServerContext* /* context */, - const rpc::component_information::AccessFloatParamsRequest* /* request */, - rpc::component_information::AccessFloatParamsResponse* response) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - if (response != nullptr) { - auto result = mavsdk::ComponentInformation::Result::NoSystem; - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - - auto result = _lazy_plugin.maybe_plugin()->access_float_params(); - - if (response != nullptr) { - fillResponseWithResult(response, result.first); - - for (auto elem : result.second) { - auto* ptr = response->add_params(); - ptr->CopyFrom(*translateToRpcFloatParam(elem).release()); - } - } - - return grpc::Status::OK; - } - - grpc::Status SubscribeFloatParam( - grpc::ServerContext* /* context */, - const mavsdk::rpc::component_information::SubscribeFloatParamRequest* /* 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::ComponentInformation::FloatParamHandle handle = - _lazy_plugin.maybe_plugin()->subscribe_float_param( - [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( - const mavsdk::ComponentInformation::FloatParamUpdate float_param) { - rpc::component_information::FloatParamResponse rpc_response; - - rpc_response.set_allocated_param_update( - translateToRpcFloatParamUpdate(float_param).release()); - - std::unique_lock lock(*subscribe_mutex); - if (!*is_finished && !writer->Write(rpc_response)) { - _lazy_plugin.maybe_plugin()->unsubscribe_float_param(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; - } - - void stop() - { - _stopped.store(true); - for (auto& prom : _stream_stop_promises) { - if (auto handle = prom.lock()) { - handle->set_value(); - } - } - } - -private: - void register_stream_stop_promise(std::weak_ptr> prom) - { - // If we have already stopped, set promise immediately and don't add it to list. - if (_stopped.load()) { - if (auto handle = prom.lock()) { - handle->set_value(); - } - } else { - _stream_stop_promises.push_back(prom); - } - } - - void unregister_stream_stop_promise(std::shared_ptr> prom) - { - for (auto it = _stream_stop_promises.begin(); it != _stream_stop_promises.end(); - /* ++it */) { - if (it->lock() == prom) { - it = _stream_stop_promises.erase(it); - } else { - ++it; - } - } - } - - LazyPlugin& _lazy_plugin; - - std::atomic _stopped{false}; - std::vector>> _stream_stop_promises{}; -}; - -} // namespace mavsdk_server -} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk_server/src/plugins/component_information_server/component_information_server_service_impl.h b/src/mavsdk_server/src/plugins/component_information_server/component_information_server_service_impl.h deleted file mode 100644 index 0fce5d9de2..0000000000 --- a/src/mavsdk_server/src/plugins/component_information_server/component_information_server_service_impl.h +++ /dev/null @@ -1,306 +0,0 @@ -// 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/component_information_server/component_information_server.proto) - -#include "component_information_server/component_information_server.grpc.pb.h" -#include "plugins/component_information_server/component_information_server.h" - -#include "mavsdk.h" - -#include "lazy_server_plugin.h" - -#include "log.h" -#include -#include -#include -#include -#include -#include -#include - -namespace mavsdk { -namespace mavsdk_server { - -template< - typename ComponentInformationServer = ComponentInformationServer, - typename LazyServerPlugin = LazyServerPlugin> - -class ComponentInformationServerServiceImpl final - : public rpc::component_information_server::ComponentInformationServerService::Service { -public: - ComponentInformationServerServiceImpl(LazyServerPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) - {} - - template - void fillResponseWithResult( - ResponseType* response, mavsdk::ComponentInformationServer::Result& result) const - { - auto rpc_result = translateToRpcResult(result); - - auto* rpc_component_information_server_result = - new rpc::component_information_server::ComponentInformationServerResult(); - rpc_component_information_server_result->set_result(rpc_result); - std::stringstream ss; - ss << result; - rpc_component_information_server_result->set_result_str(ss.str()); - - response->set_allocated_component_information_server_result( - rpc_component_information_server_result); - } - - static std::unique_ptr - translateToRpcFloatParam(const mavsdk::ComponentInformationServer::FloatParam& float_param) - { - auto rpc_obj = std::make_unique(); - - rpc_obj->set_name(float_param.name); - - rpc_obj->set_short_description(float_param.short_description); - - rpc_obj->set_long_description(float_param.long_description); - - rpc_obj->set_unit(float_param.unit); - - rpc_obj->set_decimal_places(float_param.decimal_places); - - rpc_obj->set_start_value(float_param.start_value); - - rpc_obj->set_default_value(float_param.default_value); - - rpc_obj->set_min_value(float_param.min_value); - - rpc_obj->set_max_value(float_param.max_value); - - return rpc_obj; - } - - static mavsdk::ComponentInformationServer::FloatParam - translateFromRpcFloatParam(const rpc::component_information_server::FloatParam& float_param) - { - mavsdk::ComponentInformationServer::FloatParam obj; - - obj.name = float_param.name(); - - obj.short_description = float_param.short_description(); - - obj.long_description = float_param.long_description(); - - obj.unit = float_param.unit(); - - obj.decimal_places = float_param.decimal_places(); - - obj.start_value = float_param.start_value(); - - obj.default_value = float_param.default_value(); - - obj.min_value = float_param.min_value(); - - obj.max_value = float_param.max_value(); - - return obj; - } - - static std::unique_ptr - translateToRpcFloatParamUpdate( - const mavsdk::ComponentInformationServer::FloatParamUpdate& float_param_update) - { - auto rpc_obj = std::make_unique(); - - rpc_obj->set_name(float_param_update.name); - - rpc_obj->set_value(float_param_update.value); - - return rpc_obj; - } - - static mavsdk::ComponentInformationServer::FloatParamUpdate translateFromRpcFloatParamUpdate( - const rpc::component_information_server::FloatParamUpdate& float_param_update) - { - mavsdk::ComponentInformationServer::FloatParamUpdate obj; - - obj.name = float_param_update.name(); - - obj.value = float_param_update.value(); - - return obj; - } - - static rpc::component_information_server::ComponentInformationServerResult::Result - translateToRpcResult(const mavsdk::ComponentInformationServer::Result& result) - { - switch (result) { - default: - LogErr() << "Unknown result enum value: " << static_cast(result); - // FALLTHROUGH - case mavsdk::ComponentInformationServer::Result::Unknown: - return rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_UNKNOWN; - case mavsdk::ComponentInformationServer::Result::Success: - return rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_SUCCESS; - case mavsdk::ComponentInformationServer::Result::DuplicateParam: - return rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_DUPLICATE_PARAM; - case mavsdk::ComponentInformationServer::Result::InvalidParamStartValue: - return rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_START_VALUE; - case mavsdk::ComponentInformationServer::Result::InvalidParamDefaultValue: - return rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_DEFAULT_VALUE; - case mavsdk::ComponentInformationServer::Result::InvalidParamName: - return rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_NAME; - case mavsdk::ComponentInformationServer::Result::NoSystem: - return rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_NO_SYSTEM; - } - } - - static mavsdk::ComponentInformationServer::Result translateFromRpcResult( - const rpc::component_information_server::ComponentInformationServerResult::Result result) - { - switch (result) { - default: - LogErr() << "Unknown result enum value: " << static_cast(result); - // FALLTHROUGH - case rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_UNKNOWN: - return mavsdk::ComponentInformationServer::Result::Unknown; - case rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_SUCCESS: - return mavsdk::ComponentInformationServer::Result::Success; - case rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_DUPLICATE_PARAM: - return mavsdk::ComponentInformationServer::Result::DuplicateParam; - case rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_START_VALUE: - return mavsdk::ComponentInformationServer::Result::InvalidParamStartValue; - case rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_DEFAULT_VALUE: - return mavsdk::ComponentInformationServer::Result::InvalidParamDefaultValue; - case rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_INVALID_PARAM_NAME: - return mavsdk::ComponentInformationServer::Result::InvalidParamName; - case rpc::component_information_server:: - ComponentInformationServerResult_Result_RESULT_NO_SYSTEM: - return mavsdk::ComponentInformationServer::Result::NoSystem; - } - } - - grpc::Status ProvideFloatParam( - grpc::ServerContext* /* context */, - const rpc::component_information_server::ProvideFloatParamRequest* request, - rpc::component_information_server::ProvideFloatParamResponse* response) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - if (response != nullptr) { - // For server plugins, this should never happen, they should always be - // constructible. - auto result = mavsdk::ComponentInformationServer::Result::Unknown; - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - - if (request == nullptr) { - LogWarn() << "ProvideFloatParam sent with a null request! Ignoring..."; - return grpc::Status::OK; - } - - auto result = _lazy_plugin.maybe_plugin()->provide_float_param( - translateFromRpcFloatParam(request->param())); - - if (response != nullptr) { - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - - grpc::Status SubscribeFloatParam( - grpc::ServerContext* /* context */, - const mavsdk::rpc::component_information_server::SubscribeFloatParamRequest* /* 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::ComponentInformationServer::FloatParamHandle handle = - _lazy_plugin.maybe_plugin()->subscribe_float_param( - [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( - const mavsdk::ComponentInformationServer::FloatParamUpdate float_param) { - rpc::component_information_server::FloatParamResponse rpc_response; - - rpc_response.set_allocated_param_update( - translateToRpcFloatParamUpdate(float_param).release()); - - std::unique_lock lock(*subscribe_mutex); - if (!*is_finished && !writer->Write(rpc_response)) { - _lazy_plugin.maybe_plugin()->unsubscribe_float_param(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; - } - - void stop() - { - _stopped.store(true); - for (auto& prom : _stream_stop_promises) { - if (auto handle = prom.lock()) { - handle->set_value(); - } - } - } - -private: - void register_stream_stop_promise(std::weak_ptr> prom) - { - // If we have already stopped, set promise immediately and don't add it to list. - if (_stopped.load()) { - if (auto handle = prom.lock()) { - handle->set_value(); - } - } else { - _stream_stop_promises.push_back(prom); - } - } - - void unregister_stream_stop_promise(std::shared_ptr> prom) - { - for (auto it = _stream_stop_promises.begin(); it != _stream_stop_promises.end(); - /* ++it */) { - if (it->lock() == prom) { - it = _stream_stop_promises.erase(it); - } else { - ++it; - } - } - } - - LazyServerPlugin& _lazy_plugin; - - std::atomic _stopped{false}; - std::vector>> _stream_stop_promises{}; -}; - -} // namespace mavsdk_server -} // namespace mavsdk \ No newline at end of file From 40fc61e37468ca55fb72161460dddc7e5c20693c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 17 Apr 2024 10:44:03 +0200 Subject: [PATCH 14/15] re2: update to current main To include this commit: https://github.com/google/re2/commit/9ebe4a22cad8a025b68a9594bdff3c047a111333 Which should fix the CI error: CMake Error at /home/runner/work/MAVSDK/MAVSDK/build/release/third_party/install/lib/cmake/re2/re2Config.cmake:15 (message): File or directory /include referenced by variable re2_INCLUDE_DIR does not exist ! --- third_party/re2/CMakeLists.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/third_party/re2/CMakeLists.txt b/third_party/re2/CMakeLists.txt index 671635f5b4..bbaa0a4d40 100644 --- a/third_party/re2/CMakeLists.txt +++ b/third_party/re2/CMakeLists.txt @@ -27,7 +27,8 @@ endforeach() ExternalProject_add( re2 - URL https://github.com/google/re2/archive/2023-11-01.tar.gz + GIT_REPOSITORY https://github.com/google/re2 + GIT_TAG b84e3ff189980a33d4a0c6fa1201aa0b3b8bab4a PREFIX re2 CMAKE_ARGS "${CMAKE_ARGS}" ) From a13aa623a21cd7b15fbd53a1e6467cf4e22b0ba8 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 26 Apr 2024 13:27:12 +1200 Subject: [PATCH 15/15] proto: update submodule Brings component metadata plugins. Signed-off-by: Julian Oes --- proto | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/proto b/proto index bc8c30b1f4..34bce6d61d 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit bc8c30b1f4aa476062dddf449a88ae7411c09d14 +Subproject commit 34bce6d61dba5f72b602bdbd31f04fceff093881