From e61c34125592848c3c9f6d9f55af4a3c10dca20b Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 26 Apr 2024 11:28:51 +1200 Subject: [PATCH] plugins: add log streaming (#2280) * plugins: add log streaming * core: wait long enough after IN_PROGRESS * log_streaming: additional length checks * log_streaming: use active flag to track state * log_streaming: add missing include * log_streaming: prevent double stopping * log_streaming: write what we have anyway --- examples/CMakeLists.txt | 1 + examples/log_streaming/CMakeLists.txt | 22 + examples/log_streaming/log_streaming.cpp | 130 ++ proto | 2 +- src/mavsdk/core/CMakeLists.txt | 2 + src/mavsdk/core/base64.cpp | 102 + src/mavsdk/core/callback_list_impl.h | 2 +- src/mavsdk/core/include/mavsdk/base64.h | 12 + src/mavsdk/core/log.cpp | 5 + src/mavsdk/core/log.h | 4 + src/mavsdk/core/mavlink_command_sender.cpp | 6 +- .../plugins/log_streaming/CMakeLists.txt | 15 + .../plugins/log_streaming/log_streaming.h | 177 ++ .../plugins/log_streaming/log_streaming.cpp | 96 + .../log_streaming/log_streaming_impl.cpp | 368 +++ .../log_streaming/log_streaming_impl.h | 58 + .../log_streaming/log_streaming.grpc.pb.cc | 167 ++ .../log_streaming/log_streaming.grpc.pb.h | 567 +++++ .../log_streaming/log_streaming.pb.cc | 1513 +++++++++++++ .../log_streaming/log_streaming.pb.h | 1983 +++++++++++++++++ src/mavsdk_server/src/grpc_server.cpp | 8 + src/mavsdk_server/src/grpc_server.h | 17 + .../log_streaming_service_impl.h | 247 ++ src/plugins.txt | 1 + 24 files changed, 5499 insertions(+), 6 deletions(-) create mode 100644 examples/log_streaming/CMakeLists.txt create mode 100644 examples/log_streaming/log_streaming.cpp create mode 100644 src/mavsdk/core/base64.cpp create mode 100644 src/mavsdk/core/include/mavsdk/base64.h create mode 100644 src/mavsdk/plugins/log_streaming/CMakeLists.txt create mode 100644 src/mavsdk/plugins/log_streaming/include/plugins/log_streaming/log_streaming.h create mode 100644 src/mavsdk/plugins/log_streaming/log_streaming.cpp create mode 100644 src/mavsdk/plugins/log_streaming/log_streaming_impl.cpp create mode 100644 src/mavsdk/plugins/log_streaming/log_streaming_impl.h create mode 100644 src/mavsdk_server/src/generated/log_streaming/log_streaming.grpc.pb.cc create mode 100644 src/mavsdk_server/src/generated/log_streaming/log_streaming.grpc.pb.h create mode 100644 src/mavsdk_server/src/generated/log_streaming/log_streaming.pb.cc create mode 100644 src/mavsdk_server/src/generated/log_streaming/log_streaming.pb.h create mode 100644 src/mavsdk_server/src/plugins/log_streaming/log_streaming_service_impl.h diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index ab19376cd4..42b7369cdd 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -25,6 +25,7 @@ add_subdirectory(geofence) add_subdirectory(gimbal) add_subdirectory(gimbal_device_tester) add_subdirectory(logfile_download) +add_subdirectory(log_streaming) add_subdirectory(manual_control) add_subdirectory(mavshell) add_subdirectory(multiple_drones) diff --git a/examples/log_streaming/CMakeLists.txt b/examples/log_streaming/CMakeLists.txt new file mode 100644 index 0000000000..19b83b4a48 --- /dev/null +++ b/examples/log_streaming/CMakeLists.txt @@ -0,0 +1,22 @@ +cmake_minimum_required(VERSION 3.10.2) + +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +project(log_streaming) + +add_executable(log_streaming + log_streaming.cpp +) + +find_package(MAVSDK REQUIRED) + +target_link_libraries(log_streaming + MAVSDK::mavsdk +) + +if(NOT MSVC) + add_compile_options(log_streaming PRIVATE -Wall -Wextra) +else() + add_compile_options(log_streaming PRIVATE -WX -W2) +endif() diff --git a/examples/log_streaming/log_streaming.cpp b/examples/log_streaming/log_streaming.cpp new file mode 100644 index 0000000000..34d99cfcfa --- /dev/null +++ b/examples/log_streaming/log_streaming.cpp @@ -0,0 +1,130 @@ +// +// Example how to stream ulog from PX4 with MAVSDK. +// + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +using namespace mavsdk; +using std::chrono::seconds; +using std::this_thread::sleep_for; + +void usage(const std::string& bin_name) +{ + std::cerr << "Usage : " << bin_name << " [--rm]\n" + << '\n' + << "Connection URL format should be :\n" + << " For TCP : tcp://[server_host][:server_port]\n" + << " For UDP : udp://[bind_host][:bind_port]\n" + << " For Serial : serial:///path/to/serial/dev[:baudrate]\n" + << "For example, to connect to the simulator use URL: udp://:14540" << std::endl; +} + +int main(int argc, char** argv) +{ + if (argc > 2) { + usage(argv[0]); + return 1; + } + + Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); + + if (connection_result != ConnectionResult::Success) { + std::cerr << "Connection failed: " << connection_result << std::endl; + return 1; + } + + auto system = mavsdk.first_autopilot(3.0); + if (!system) { + std::cerr << "Timed out waiting for system\n"; + return 1; + } + + // Create file to log to. + // Get current time + auto now = std::chrono::system_clock::now(); + auto in_time_t = std::chrono::system_clock::to_time_t(now); + + // Convert time_t to tm struct + struct tm buf; + localtime_r(&in_time_t, &buf); + + // Create a stringstream to hold the filename + std::stringstream ss; + + // Format the time into the stringstream + ss << std::put_time(&buf, "%Y-%m-%d_%H-%M-%S") << ".ulg"; + + // Convert stringstream to string to use as filename + std::string filename = ss.str(); + + // Open the file + std::ofstream file(filename, std::ios::binary); + + if (!file.is_open()) { + std::cerr << "Could not open file with name '" << ss.str() << "'"; + return 1; + } + + // Instantiate plugins. + auto log_streaming = LogStreaming{system.value()}; + + size_t bytes_written = 0; + size_t bytes_written_since_last = 0; + auto last_time = std::chrono::steady_clock::now(); + + log_streaming.subscribe_log_streaming_raw([&](LogStreaming::LogStreamingRaw raw) { + const auto bytes = mavsdk::base64_decode(raw.data); + file.write(reinterpret_cast(bytes.data()), bytes.size()); + bytes_written += bytes.size(); + bytes_written_since_last += bytes.size(); + + auto now = std::chrono::steady_clock::now(); + std::chrono::duration elapsed = now - last_time; + + if (elapsed.count() >= 1.0) { + // More than or equal to one second has passed + double seconds = elapsed.count(); + double rate_kib_per_second = (bytes_written_since_last / 1024.0) / seconds; + + std::cout << "Wrote " << std::setprecision(3) << bytes_written / 1024.0 / 1024.0 + << " MiB (" << rate_kib_per_second << " KiB/s)" << std::endl; + + // Reset timer and counter + last_time = now; + bytes_written_since_last = 0; + } + }); + + auto result = log_streaming.start_log_streaming(); + if (result != LogStreaming::Result::Success) { + std::cerr << "Log streaming start failed." << std::endl; + return 1; + } + + for (unsigned i = 0; i < 10; ++i) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + } + + result = log_streaming.stop_log_streaming(); + if (result != LogStreaming::Result::Success) { + std::cerr << "Log streaming stop failed." << std::endl; + return 1; + } + + // Give it time to wrap up all logging data + std::this_thread::sleep_for(std::chrono::seconds(3)); + + file.close(); + + return 0; +} diff --git a/proto b/proto index debaacd172..414456516c 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit debaacd17271803520a264120165d19bf6d24c37 +Subproject commit 414456516c1bf7ed8af27d2d3a7e817c57654c94 diff --git a/src/mavsdk/core/CMakeLists.txt b/src/mavsdk/core/CMakeLists.txt index 331061879e..2baa885f37 100644 --- a/src/mavsdk/core/CMakeLists.txt +++ b/src/mavsdk/core/CMakeLists.txt @@ -14,6 +14,7 @@ configure_file(include/mavsdk/mavlink_include.h.in include/mavsdk/mavlink_includ target_sources(mavsdk PRIVATE + base64.cpp call_every_handler.cpp connection.cpp connection_result.cpp @@ -150,6 +151,7 @@ install(TARGETS mavsdk install(FILES include/mavsdk/autopilot.h + include/mavsdk/base64.h include/mavsdk/connection_result.h include/mavsdk/deprecated.h include/mavsdk/handle.h diff --git a/src/mavsdk/core/base64.cpp b/src/mavsdk/core/base64.cpp new file mode 100644 index 0000000000..e4786d61dd --- /dev/null +++ b/src/mavsdk/core/base64.cpp @@ -0,0 +1,102 @@ +#include "base64.h" + +namespace mavsdk { + +static const std::string base64_chars = "ABCDEFGHIJKLMNOPQRSTUVWXYZ" + "abcdefghijklmnopqrstuvwxyz" + "0123456789+/"; + +static inline bool is_base64(uint8_t c) +{ + return (isalnum(c) || (c == '+') || (c == '/')); +} + +std::string base64_encode(std::vector& raw) +{ + uint8_t* buf = raw.data(); + size_t bufLen = raw.size(); + + std::string ret; + int i = 0; + int j = 0; + uint8_t char_array_3[3]; + uint8_t char_array_4[4]; + + while (bufLen--) { + char_array_3[i++] = *(buf++); + if (i == 3) { + char_array_4[0] = (char_array_3[0] & 0xfc) >> 2; + char_array_4[1] = ((char_array_3[0] & 0x03) << 4) + ((char_array_3[1] & 0xf0) >> 4); + char_array_4[2] = ((char_array_3[1] & 0x0f) << 2) + ((char_array_3[2] & 0xc0) >> 6); + char_array_4[3] = char_array_3[2] & 0x3f; + + for (i = 0; (i < 4); i++) + ret += base64_chars[char_array_4[i]]; + i = 0; + } + } + + if (i) { + for (j = i; j < 3; j++) + char_array_3[j] = '\0'; + + char_array_4[0] = (char_array_3[0] & 0xfc) >> 2; + char_array_4[1] = ((char_array_3[0] & 0x03) << 4) + ((char_array_3[1] & 0xf0) >> 4); + char_array_4[2] = ((char_array_3[1] & 0x0f) << 2) + ((char_array_3[2] & 0xc0) >> 6); + char_array_4[3] = char_array_3[2] & 0x3f; + + for (j = 0; (j < i + 1); j++) + ret += base64_chars[char_array_4[j]]; + + while ((i++ < 3)) + ret += '='; + } + + return ret; +} + +std::vector base64_decode(std::string const& encoded_string) +{ + int in_len = encoded_string.size(); + int i = 0; + int j = 0; + int in_ = 0; + uint8_t char_array_4[4], char_array_3[3]; + std::vector ret; + + while (in_len-- && (encoded_string[in_] != '=') && is_base64(encoded_string[in_])) { + char_array_4[i++] = encoded_string[in_]; + in_++; + if (i == 4) { + for (i = 0; i < 4; i++) + char_array_4[i] = base64_chars.find(char_array_4[i]); + + char_array_3[0] = (char_array_4[0] << 2) + ((char_array_4[1] & 0x30) >> 4); + char_array_3[1] = ((char_array_4[1] & 0xf) << 4) + ((char_array_4[2] & 0x3c) >> 2); + char_array_3[2] = ((char_array_4[2] & 0x3) << 6) + char_array_4[3]; + + for (i = 0; (i < 3); i++) + ret.push_back(char_array_3[i]); + i = 0; + } + } + + if (i) { + for (j = i; j < 4; j++) + char_array_4[j] = 0; + + for (j = 0; j < 4; j++) + char_array_4[j] = base64_chars.find(char_array_4[j]); + + char_array_3[0] = (char_array_4[0] << 2) + ((char_array_4[1] & 0x30) >> 4); + char_array_3[1] = ((char_array_4[1] & 0xf) << 4) + ((char_array_4[2] & 0x3c) >> 2); + char_array_3[2] = ((char_array_4[2] & 0x3) << 6) + char_array_4[3]; + + for (j = 0; (j < i - 1); j++) + ret.push_back(char_array_3[j]); + } + + return ret; +} + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/core/callback_list_impl.h b/src/mavsdk/core/callback_list_impl.h index a5a1a8b95a..ec62ece003 100644 --- a/src/mavsdk/core/callback_list_impl.h +++ b/src/mavsdk/core/callback_list_impl.h @@ -100,7 +100,7 @@ template class CallbackListImpl { { std::lock_guard remove_later_lock(_remove_later_mutex); - // We could probably just grab the lock here but it's safer not to + // We could probably just grab the lock here, but it's safer not to // acquire both locks to avoid deadlocks. if (_mutex.try_lock()) { if (_remove_all_later) { diff --git a/src/mavsdk/core/include/mavsdk/base64.h b/src/mavsdk/core/include/mavsdk/base64.h new file mode 100644 index 0000000000..831960d150 --- /dev/null +++ b/src/mavsdk/core/include/mavsdk/base64.h @@ -0,0 +1,12 @@ +#include +#include +#include + +// Taken from https://stackoverflow.com/a/13935718/8548472 + +namespace mavsdk { + +std::string base64_encode(std::vector& raw); +std::vector base64_decode(const std::string& str); + +} // namespace mavsdk diff --git a/src/mavsdk/core/log.cpp b/src/mavsdk/core/log.cpp index a6d035ce06..7dd4352603 100644 --- a/src/mavsdk/core/log.cpp +++ b/src/mavsdk/core/log.cpp @@ -25,6 +25,11 @@ namespace mavsdk { static std::mutex callback_mutex_{}; static log::Callback callback_{nullptr}; +std::ostream& operator<<(std::ostream& os, std::byte b) +{ + return os << std::bitset<8>(std::to_integer(b)); +} + log::Callback& log::get_callback() { std::lock_guard lock(callback_mutex_); diff --git a/src/mavsdk/core/log.h b/src/mavsdk/core/log.h index 9dbd92b5d9..d71cda32bf 100644 --- a/src/mavsdk/core/log.h +++ b/src/mavsdk/core/log.h @@ -1,5 +1,7 @@ #pragma once +#include +#include #include #include #include "log_callback.h" @@ -30,6 +32,8 @@ namespace mavsdk { static std::mutex log_mutex_{}; +std::ostream& operator<<(std::ostream& os, std::byte b); + enum class Color { Red, Green, Yellow, Blue, Gray, Reset }; void set_color(Color color); diff --git a/src/mavsdk/core/mavlink_command_sender.cpp b/src/mavsdk/core/mavlink_command_sender.cpp index e535b08084..652613fa0f 100644 --- a/src/mavsdk/core/mavlink_command_sender.cpp +++ b/src/mavsdk/core/mavlink_command_sender.cpp @@ -238,15 +238,13 @@ void MavlinkCommandSender::receive_command_ack(mavlink_message_t message) } // If we get a progress update, we can raise the timeout // to something higher because we know the initial command - // has arrived. A possible timeout for this case is the initial - // timeout * the possible retries because this should match the - // case where there is no progress update, and we keep trying. + // has arrived. _system_impl.unregister_timeout_handler(work->timeout_cookie); _system_impl.register_timeout_handler( [this, identification = work->identification] { receive_timeout(identification); }, - work->retries_to_do * work->timeout_s, + 3.0, &work->timeout_cookie); temp_result = { diff --git a/src/mavsdk/plugins/log_streaming/CMakeLists.txt b/src/mavsdk/plugins/log_streaming/CMakeLists.txt new file mode 100644 index 0000000000..34b9849980 --- /dev/null +++ b/src/mavsdk/plugins/log_streaming/CMakeLists.txt @@ -0,0 +1,15 @@ +target_sources(mavsdk + PRIVATE + log_streaming.cpp + log_streaming_impl.cpp +) + +target_include_directories(mavsdk PUBLIC + $ + $ + ) + +install(FILES + include/plugins/log_streaming/log_streaming.h + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/mavsdk/plugins/log_streaming +) \ No newline at end of file diff --git a/src/mavsdk/plugins/log_streaming/include/plugins/log_streaming/log_streaming.h b/src/mavsdk/plugins/log_streaming/include/plugins/log_streaming/log_streaming.h new file mode 100644 index 0000000000..67179ff4b6 --- /dev/null +++ b/src/mavsdk/plugins/log_streaming/include/plugins/log_streaming/log_streaming.h @@ -0,0 +1,177 @@ +// 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/log_streaming/log_streaming.proto) + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "plugin_base.h" + +#include "handle.h" + +namespace mavsdk { + +class System; +class LogStreamingImpl; + +/** + * @brief Provide log streaming data. + */ +class LogStreaming : public PluginBase { +public: + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto log_streaming = LogStreaming(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit LogStreaming(System& system); // deprecated + + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto log_streaming = LogStreaming(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit LogStreaming(std::shared_ptr system); // new + + /** + * @brief Destructor (internal use only). + */ + ~LogStreaming() override; + + /** + * @brief Raw logging data type + */ + struct LogStreamingRaw { + std::string data{}; /**< @brief Ulog file stream data encoded as base64 */ + }; + + /** + * @brief Equal operator to compare two `LogStreaming::LogStreamingRaw` objects. + * + * @return `true` if items are equal. + */ + friend bool + operator==(const LogStreaming::LogStreamingRaw& lhs, const LogStreaming::LogStreamingRaw& rhs); + + /** + * @brief Stream operator to print information about a `LogStreaming::LogStreamingRaw`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, LogStreaming::LogStreamingRaw const& log_streaming_raw); + + /** + * @brief Possible results returned for logging requests + */ + enum class Result { + Success, /**< @brief Request succeeded. */ + NoSystem, /**< @brief No system connected. */ + ConnectionError, /**< @brief Connection error. */ + Busy, /**< @brief System busy. */ + CommandDenied, /**< @brief Command denied. */ + Timeout, /**< @brief Timeout. */ + Unsupported, /**< @brief Unsupported. */ + Unknown, /**< @brief Unknown error. */ + }; + + /** + * @brief Stream operator to print information about a `LogStreaming::Result`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, LogStreaming::Result const& result); + + /** + * @brief Callback type for asynchronous LogStreaming calls. + */ + using ResultCallback = std::function; + + /** + * @brief Start streaming logging data. + * + * This function is non-blocking. See 'start_log_streaming' for the blocking counterpart. + */ + void start_log_streaming_async(const ResultCallback callback); + + /** + * @brief Start streaming logging data. + * + * This function is blocking. See 'start_log_streaming_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result start_log_streaming() const; + + /** + * @brief Stop streaming logging data. + * + * This function is non-blocking. See 'stop_log_streaming' for the blocking counterpart. + */ + void stop_log_streaming_async(const ResultCallback callback); + + /** + * @brief Stop streaming logging data. + * + * This function is blocking. See 'stop_log_streaming_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result stop_log_streaming() const; + + /** + * @brief Callback type for subscribe_log_streaming_raw. + */ + using LogStreamingRawCallback = std::function; + + /** + * @brief Handle type for subscribe_log_streaming_raw. + */ + using LogStreamingRawHandle = Handle; + + /** + * @brief Subscribe to logging messages + */ + LogStreamingRawHandle subscribe_log_streaming_raw(const LogStreamingRawCallback& callback); + + /** + * @brief Unsubscribe from subscribe_log_streaming_raw + */ + void unsubscribe_log_streaming_raw(LogStreamingRawHandle handle); + + /** + * @brief Copy constructor. + */ + LogStreaming(const LogStreaming& other); + + /** + * @brief Equality operator (object is not copyable). + */ + const LogStreaming& operator=(const LogStreaming&) = 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/log_streaming/log_streaming.cpp b/src/mavsdk/plugins/log_streaming/log_streaming.cpp new file mode 100644 index 0000000000..5859489287 --- /dev/null +++ b/src/mavsdk/plugins/log_streaming/log_streaming.cpp @@ -0,0 +1,96 @@ +// 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/log_streaming/log_streaming.proto) + +#include + +#include "log_streaming_impl.h" +#include "plugins/log_streaming/log_streaming.h" + +namespace mavsdk { + +using LogStreamingRaw = LogStreaming::LogStreamingRaw; + +LogStreaming::LogStreaming(System& system) : + PluginBase(), + _impl{std::make_unique(system)} +{} + +LogStreaming::LogStreaming(std::shared_ptr system) : + PluginBase(), + _impl{std::make_unique(system)} +{} + +LogStreaming::~LogStreaming() {} + +void LogStreaming::start_log_streaming_async(const ResultCallback callback) +{ + _impl->start_log_streaming_async(callback); +} + +LogStreaming::Result LogStreaming::start_log_streaming() const +{ + return _impl->start_log_streaming(); +} + +void LogStreaming::stop_log_streaming_async(const ResultCallback callback) +{ + _impl->stop_log_streaming_async(callback); +} + +LogStreaming::Result LogStreaming::stop_log_streaming() const +{ + return _impl->stop_log_streaming(); +} + +LogStreaming::LogStreamingRawHandle +LogStreaming::subscribe_log_streaming_raw(const LogStreamingRawCallback& callback) +{ + return _impl->subscribe_log_streaming_raw(callback); +} + +void LogStreaming::unsubscribe_log_streaming_raw(LogStreamingRawHandle handle) +{ + _impl->unsubscribe_log_streaming_raw(handle); +} + +bool operator==(const LogStreaming::LogStreamingRaw& lhs, const LogStreaming::LogStreamingRaw& rhs) +{ + return (rhs.data == lhs.data); +} + +std::ostream& operator<<(std::ostream& str, LogStreaming::LogStreamingRaw const& log_streaming_raw) +{ + str << std::setprecision(15); + str << "log_streaming_raw:" << '\n' << "{\n"; + str << " data: " << log_streaming_raw.data << '\n'; + str << '}'; + return str; +} + +std::ostream& operator<<(std::ostream& str, LogStreaming::Result const& result) +{ + switch (result) { + case LogStreaming::Result::Success: + return str << "Success"; + case LogStreaming::Result::NoSystem: + return str << "No System"; + case LogStreaming::Result::ConnectionError: + return str << "Connection Error"; + case LogStreaming::Result::Busy: + return str << "Busy"; + case LogStreaming::Result::CommandDenied: + return str << "Command Denied"; + case LogStreaming::Result::Timeout: + return str << "Timeout"; + case LogStreaming::Result::Unsupported: + return str << "Unsupported"; + case LogStreaming::Result::Unknown: + return str << "Unknown"; + default: + return str << "Unknown"; + } +} + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/log_streaming/log_streaming_impl.cpp b/src/mavsdk/plugins/log_streaming/log_streaming_impl.cpp new file mode 100644 index 0000000000..53b2ced3a0 --- /dev/null +++ b/src/mavsdk/plugins/log_streaming/log_streaming_impl.cpp @@ -0,0 +1,368 @@ +#include +#include + +#include "log_streaming_impl.h" +#include "plugins/log_streaming/log_streaming.h" +#include "callback_list.tpp" +#include "base64.h" + +// Note: the implementation below is mostly inspired by the pymavlink +// implementation written by Beat Küng: +// https://github.com/PX4/PX4-Autopilot/blob/main/Tools/mavlink_ulog_streaming.py +// +// For more information about the ulog protocol, visit: +// https://docs.px4.io/main/en/dev_log/ulog_file_format.html + +namespace mavsdk { + +template class CallbackList; + +LogStreamingImpl::LogStreamingImpl(System& system) : PluginImplBase(system) +{ + _system_impl->register_plugin(this); +} + +LogStreamingImpl::LogStreamingImpl(std::shared_ptr system) : + PluginImplBase(std::move(system)) +{ + _system_impl->register_plugin(this); +} + +LogStreamingImpl::~LogStreamingImpl() +{ + _system_impl->unregister_plugin(this); +} + +void LogStreamingImpl::init() +{ + if (const char* env_p = std::getenv("MAVSDK_LOG_STREAMING_DEBUGGING")) { + if (std::string(env_p) == "1") { + LogDebug() << "Log streaming debugging is on."; + _debugging = true; + } + } + + _system_impl->register_mavlink_message_handler( + MAVLINK_MSG_ID_LOGGING_DATA, + [this](const mavlink_message_t& message) { process_logging_data(message); }, + this); + _system_impl->register_mavlink_message_handler( + MAVLINK_MSG_ID_LOGGING_DATA_ACKED, + [this](const mavlink_message_t& message) { process_logging_data_acked(message); }, + this); +} + +void LogStreamingImpl::deinit() +{ + auto is_active = [this]() { + std::lock_guard lock(_mutex); + return _active; + }(); + + if (is_active) { + // We try to stop log streaming before we leave but without waiting for a result. + stop_log_streaming_async(nullptr); + } +} + +void LogStreamingImpl::enable() {} + +void LogStreamingImpl::disable() {} + +void LogStreamingImpl::start_log_streaming_async(const LogStreaming::ResultCallback& callback) +{ + { + std::lock_guard lock(_mutex); + _maybe_current_sequence = {}; + _active = true; + } + + MavlinkCommandSender::CommandLong command{}; + command.command = MAV_CMD_LOGGING_START; + command.params.maybe_param1 = 0.0f; // ulog + + _system_impl->send_command_async(command, [=](MavlinkCommandSender::Result result, float) { + if (result != MavlinkCommandSender::Result::InProgress) { + if (callback) { + _system_impl->call_user_callback( + [=]() { callback(log_streaming_result_from_command_result(result)); }); + } + } + }); +} + +LogStreaming::Result LogStreamingImpl::start_log_streaming() +{ + auto prom = std::promise{}; + auto fut = prom.get_future(); + + start_log_streaming_async([&](LogStreaming::Result result) { prom.set_value(result); }); + + return fut.get(); +} + +void LogStreamingImpl::stop_log_streaming_async(const LogStreaming::ResultCallback& callback) +{ + MavlinkCommandSender::CommandLong command{}; + command.command = MAV_CMD_LOGGING_STOP; + + _system_impl->send_command_async(command, [=](MavlinkCommandSender::Result result, float) { + if (result != MavlinkCommandSender::Result::InProgress) { + if (callback) { + _system_impl->call_user_callback( + [=]() { callback(log_streaming_result_from_command_result(result)); }); + } + } + }); + + std::lock_guard lock(_mutex); + _maybe_current_sequence = {}; + _active = false; +} + +LogStreaming::Result LogStreamingImpl::stop_log_streaming() +{ + auto prom = std::promise{}; + auto fut = prom.get_future(); + + stop_log_streaming_async([&](LogStreaming::Result result) { prom.set_value(result); }); + + return fut.get(); +} + +LogStreaming::LogStreamingRawHandle +LogStreamingImpl::subscribe_log_streaming_raw(const LogStreaming::LogStreamingRawCallback& callback) +{ + std::lock_guard lock(_mutex); + auto handle = _subscription_callbacks.subscribe(callback); + + return handle; +} + +void LogStreamingImpl::unsubscribe_log_streaming_raw(LogStreaming::LogStreamingRawHandle handle) +{ + std::lock_guard lock(_mutex); + _subscription_callbacks.unsubscribe(handle); +} + +void LogStreamingImpl::process_logging_data(const mavlink_message_t& message) +{ + if (!_active) { + if (_debugging) { + LogDebug() << "Ignoring logging data because we're not active"; + } + return; + } + + mavlink_logging_data_t logging_data; + mavlink_msg_logging_data_decode(&message, &logging_data); + + if (logging_data.target_system != _system_impl->get_own_system_id() || + logging_data.target_component != _system_impl->get_own_component_id()) { + LogWarn() << "Logging data with wrong target " << std::to_string(logging_data.target_system) + << '/' << std::to_string(logging_data.target_component) << " instead of " + << std::to_string(_system_impl->get_own_system_id()) << '/' + << std::to_string(_system_impl->get_own_component_id()); + return; + } + + if (_debugging) { + LogDebug() << "Received logging data with len: " << std::to_string(logging_data.length) + << ", first message: " << std::to_string(logging_data.first_message_offset) + << ", sequence: " << logging_data.sequence; + } + + if (logging_data.length > sizeof(logging_data.data)) { + LogWarn() << "Invalid length"; + return; + } + + std::lock_guard lock(_mutex); + check_sequence(logging_data.sequence); + + if (logging_data.first_message_offset == std::numeric_limits::max()) { + _ulog_data.insert( + _ulog_data.end(), logging_data.data, logging_data.data + logging_data.length); + } else { + if (logging_data.first_message_offset > sizeof(logging_data.data)) { + LogWarn() << "Invalid first_message_offset"; + return; + } + + _ulog_data.insert( + _ulog_data.end(), + logging_data.data, + logging_data.data + logging_data.first_message_offset); + process_message(); + _ulog_data.clear(); + + _ulog_data.insert( + _ulog_data.end(), + logging_data.data + logging_data.first_message_offset, + logging_data.data + logging_data.length); + } +} + +void LogStreamingImpl::process_logging_data_acked(const mavlink_message_t& message) +{ + if (!_active) { + if (_debugging) { + LogDebug() << "Ignoring logging data acked because we're not active"; + } + return; + } + + mavlink_logging_data_acked_t logging_data_acked; + mavlink_msg_logging_data_acked_decode(&message, &logging_data_acked); + + if (logging_data_acked.target_system != _system_impl->get_own_system_id() || + logging_data_acked.target_component != _system_impl->get_own_component_id()) { + LogWarn() << "Logging data acked with wrong target " + << std::to_string(logging_data_acked.target_system) << '/' + << std::to_string(logging_data_acked.target_component) << " instead of " + << std::to_string(_system_impl->get_own_system_id()) << '/' + << std::to_string(_system_impl->get_own_component_id()); + return; + } + + _system_impl->queue_message( + [target_system = message.sysid, + target_component = message.compid, + sequence = logging_data_acked.sequence](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t response_message; + mavlink_msg_logging_ack_pack_chan( + mavlink_address.system_id, + mavlink_address.component_id, + channel, + &response_message, + target_system, + target_component, + sequence); + return response_message; + }); + + if (_debugging) { + LogInfo() << "Received logging data acked with len: " + << std::to_string(logging_data_acked.length) + << ", first message: " << std::to_string(logging_data_acked.first_message_offset) + << ", sequence: " << logging_data_acked.sequence; + } + + if (logging_data_acked.length > sizeof(logging_data_acked.data)) { + LogWarn() << "Invalid length"; + return; + } + + std::lock_guard lock(_mutex); + check_sequence(logging_data_acked.sequence); + + if (logging_data_acked.first_message_offset == std::numeric_limits::max()) { + _ulog_data.insert( + _ulog_data.end(), + logging_data_acked.data, + logging_data_acked.data + logging_data_acked.length); + } else { + if (logging_data_acked.first_message_offset > sizeof(logging_data_acked.data)) { + LogWarn() << "Invalid first_message_offset"; + return; + } + + _ulog_data.insert( + _ulog_data.end(), + logging_data_acked.data, + logging_data_acked.data + logging_data_acked.first_message_offset); + process_message(); + _ulog_data.clear(); + + _ulog_data.insert( + _ulog_data.end(), + logging_data_acked.data + logging_data_acked.first_message_offset, + logging_data_acked.data + logging_data_acked.length); + } +} + +void LogStreamingImpl::check_sequence(uint16_t sequence) +{ + // Assume we have lock. + + if (!_maybe_current_sequence) { + // This is the first time we use the sequence. + _maybe_current_sequence = sequence; + return; + } + + if (_maybe_current_sequence.value() == sequence) { + // Duplicate + return; + } + + if (sequence > _maybe_current_sequence.value()) { + // No wrap around. + uint16_t drop = (sequence - 1 - _maybe_current_sequence.value()); + _drops += drop; + if (drop > 0 && _debugging) { + LogDebug() << "Dropped: " << drop << " (no wrap around), overall: " << _drops; + } + } else { + // Wrap around! + uint16_t drop = + (sequence + std::numeric_limits::max() - 1 - _maybe_current_sequence.value()); + _drops += drop; + if (drop > 0 && _debugging) { + LogDebug() << "Dropped: " << drop << " (with wrap around), overall: " << _drops; + } + } + + _maybe_current_sequence = sequence; +} + +void LogStreamingImpl::process_message() +{ + // Assumes lock. + + if (_debugging) { + LogDebug() << "Processing ulog message with size " << _ulog_data.size(); + } + + // We don't check the magic and version. That's up to the log viewer to parse. + + // Convert to base64 + LogStreaming::LogStreamingRaw part; + part.data = base64_encode(_ulog_data); + + // Let's pass it to the user. + if (!_subscription_callbacks.empty()) { + _subscription_callbacks.queue( + part, [this](const auto& func) { _system_impl->call_user_callback(func); }); + } +} + +LogStreaming::Result +LogStreamingImpl::log_streaming_result_from_command_result(MavlinkCommandSender::Result result) +{ + switch (result) { + case MavlinkCommandSender::Result::Success: + return LogStreaming::Result::Success; + case MavlinkCommandSender::Result::NoSystem: + return LogStreaming::Result::NoSystem; + case MavlinkCommandSender::Result::ConnectionError: + return LogStreaming::Result::ConnectionError; + case MavlinkCommandSender::Result::Busy: + return LogStreaming::Result::Busy; + case MavlinkCommandSender::Result::Denied: + return LogStreaming::Result::CommandDenied; + case MavlinkCommandSender::Result::Unsupported: + return LogStreaming::Result::Unsupported; + case MavlinkCommandSender::Result::Timeout: + return LogStreaming::Result::Timeout; + case MavlinkCommandSender::Result::InProgress: + case MavlinkCommandSender::Result::TemporarilyRejected: + case MavlinkCommandSender::Result::Failed: + case MavlinkCommandSender::Result::Cancelled: + case MavlinkCommandSender::Result::UnknownError: + default: + return LogStreaming::Result::Unknown; + } +} + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/log_streaming/log_streaming_impl.h b/src/mavsdk/plugins/log_streaming/log_streaming_impl.h new file mode 100644 index 0000000000..35f80ba054 --- /dev/null +++ b/src/mavsdk/plugins/log_streaming/log_streaming_impl.h @@ -0,0 +1,58 @@ +#pragma once + +#include "plugins/log_streaming/log_streaming.h" + +#include "plugin_impl_base.h" +#include "callback_list.h" + +#include +#include + +namespace mavsdk { + +class LogStreamingImpl : public PluginImplBase { +public: + explicit LogStreamingImpl(System& system); + explicit LogStreamingImpl(std::shared_ptr system); + + ~LogStreamingImpl() override; + + void init() override; + void deinit() override; + + void enable() override; + void disable() override; + + void start_log_streaming_async(const LogStreaming::ResultCallback& callback); + + LogStreaming::Result start_log_streaming(); + + void stop_log_streaming_async(const LogStreaming::ResultCallback& callback); + + LogStreaming::Result stop_log_streaming(); + + LogStreaming::LogStreamingRawHandle + subscribe_log_streaming_raw(const LogStreaming::LogStreamingRawCallback& callback); + + void unsubscribe_log_streaming_raw(LogStreaming::LogStreamingRawHandle handle); + +private: + void process_logging_data(const mavlink_message_t& message); + void process_logging_data_acked(const mavlink_message_t& message); + void check_sequence(uint16_t sequence); + void process_message(); + + static LogStreaming::Result + log_streaming_result_from_command_result(MavlinkCommandSender::Result result); + + std::mutex _mutex{}; + CallbackList _subscription_callbacks{}; + std::optional _maybe_current_sequence{}; + unsigned _drops{0}; + std::vector _ulog_data{}; + bool _active = false; + + bool _debugging{false}; +}; + +} // namespace mavsdk diff --git a/src/mavsdk_server/src/generated/log_streaming/log_streaming.grpc.pb.cc b/src/mavsdk_server/src/generated/log_streaming/log_streaming.grpc.pb.cc new file mode 100644 index 0000000000..00f2f4d1a4 --- /dev/null +++ b/src/mavsdk_server/src/generated/log_streaming/log_streaming.grpc.pb.cc @@ -0,0 +1,167 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: log_streaming/log_streaming.proto + +#include "log_streaming/log_streaming.pb.h" +#include "log_streaming/log_streaming.grpc.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +namespace mavsdk { +namespace rpc { +namespace log_streaming { + +static const char* LogStreamingService_method_names[] = { + "/mavsdk.rpc.log_streaming.LogStreamingService/StartLogStreaming", + "/mavsdk.rpc.log_streaming.LogStreamingService/StopLogStreaming", + "/mavsdk.rpc.log_streaming.LogStreamingService/SubscribeLogStreamingRaw", +}; + +std::unique_ptr< LogStreamingService::Stub> LogStreamingService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { + (void)options; + std::unique_ptr< LogStreamingService::Stub> stub(new LogStreamingService::Stub(channel, options)); + return stub; +} + +LogStreamingService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) + : channel_(channel), rpcmethod_StartLogStreaming_(LogStreamingService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_StopLogStreaming_(LogStreamingService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeLogStreamingRaw_(LogStreamingService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + {} + +::grpc::Status LogStreamingService::Stub::StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_StartLogStreaming_, context, request, response); +} + +void LogStreamingService::Stub::async::StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_StartLogStreaming_, context, request, response, std::move(f)); +} + +void LogStreamingService::Stub::async::StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_StartLogStreaming_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>* LogStreamingService::Stub::PrepareAsyncStartLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse, ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_StartLogStreaming_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>* LogStreamingService::Stub::AsyncStartLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncStartLogStreamingRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status LogStreamingService::Stub::StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_StopLogStreaming_, context, request, response); +} + +void LogStreamingService::Stub::async::StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_StopLogStreaming_, context, request, response, std::move(f)); +} + +void LogStreamingService::Stub::async::StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_StopLogStreaming_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* LogStreamingService::Stub::PrepareAsyncStopLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse, ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_StopLogStreaming_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* LogStreamingService::Stub::AsyncStopLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncStopLogStreamingRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::ClientReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* LogStreamingService::Stub::SubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>::Create(channel_.get(), rpcmethod_SubscribeLogStreamingRaw_, context, request); +} + +void LogStreamingService::Stub::async::SubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeLogStreamingRaw_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* LogStreamingService::Stub::AsyncSubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeLogStreamingRaw_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* LogStreamingService::Stub::PrepareAsyncSubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeLogStreamingRaw_, context, request, false, nullptr); +} + +LogStreamingService::Service::Service() { + AddMethod(new ::grpc::internal::RpcServiceMethod( + LogStreamingService_method_names[0], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< LogStreamingService::Service, ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](LogStreamingService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* req, + ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* resp) { + return service->StartLogStreaming(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + LogStreamingService_method_names[1], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< LogStreamingService::Service, ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](LogStreamingService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* req, + ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* resp) { + return service->StopLogStreaming(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + LogStreamingService_method_names[2], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< LogStreamingService::Service, ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest, ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>( + [](LogStreamingService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* writer) { + return service->SubscribeLogStreamingRaw(ctx, req, writer); + }, this))); +} + +LogStreamingService::Service::~Service() { +} + +::grpc::Status LogStreamingService::Service::StartLogStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status LogStreamingService::Service::StopLogStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status LogStreamingService::Service::SubscribeLogStreamingRaw(::grpc::ServerContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + + +} // namespace mavsdk +} // namespace rpc +} // namespace log_streaming + diff --git a/src/mavsdk_server/src/generated/log_streaming/log_streaming.grpc.pb.h b/src/mavsdk_server/src/generated/log_streaming/log_streaming.grpc.pb.h new file mode 100644 index 0000000000..6bb173caff --- /dev/null +++ b/src/mavsdk_server/src/generated/log_streaming/log_streaming.grpc.pb.h @@ -0,0 +1,567 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: log_streaming/log_streaming.proto +#ifndef GRPC_log_5fstreaming_2flog_5fstreaming_2eproto__INCLUDED +#define GRPC_log_5fstreaming_2flog_5fstreaming_2eproto__INCLUDED + +#include "log_streaming/log_streaming.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 log_streaming { + +// Provide log streaming data. +class LogStreamingService final { + public: + static constexpr char const* service_full_name() { + return "mavsdk.rpc.log_streaming.LogStreamingService"; + } + class StubInterface { + public: + virtual ~StubInterface() {} + // Start streaming logging data. + virtual ::grpc::Status StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>> AsyncStartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>>(AsyncStartLogStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>> PrepareAsyncStartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>>(PrepareAsyncStartLogStreamingRaw(context, request, cq)); + } + // Stop streaming logging data. + virtual ::grpc::Status StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>> AsyncStopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>>(AsyncStopLogStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>> PrepareAsyncStopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>>(PrepareAsyncStopLogStreamingRaw(context, request, cq)); + } + // Subscribe to logging messages + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>> SubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>>(SubscribeLogStreamingRawRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>> AsyncSubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>>(AsyncSubscribeLogStreamingRawRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>> PrepareAsyncSubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>>(PrepareAsyncSubscribeLogStreamingRawRaw(context, request, cq)); + } + class async_interface { + public: + virtual ~async_interface() {} + // Start streaming logging data. + virtual void StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response, std::function) = 0; + virtual void StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Stop streaming logging data. + virtual void StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response, std::function) = 0; + virtual void StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to logging messages + virtual void SubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* 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::log_streaming::StartLogStreamingResponse>* AsyncStartLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>* PrepareAsyncStartLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* AsyncStopLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* PrepareAsyncStopLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* SubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* AsyncSubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* PrepareAsyncSubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& 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 StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>> AsyncStartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>>(AsyncStartLogStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>> PrepareAsyncStartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>>(PrepareAsyncStartLogStreamingRaw(context, request, cq)); + } + ::grpc::Status StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>> AsyncStopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>>(AsyncStopLogStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>> PrepareAsyncStopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>>(PrepareAsyncStopLogStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>> SubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>>(SubscribeLogStreamingRawRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>> AsyncSubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>>(AsyncSubscribeLogStreamingRawRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>> PrepareAsyncSubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>>(PrepareAsyncSubscribeLogStreamingRawRaw(context, request, cq)); + } + class async final : + public StubInterface::async_interface { + public: + void StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response, std::function) override; + void StartLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response, std::function) override; + void StopLogStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* 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::log_streaming::StartLogStreamingResponse>* AsyncStartLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>* PrepareAsyncStartLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* AsyncStopLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* PrepareAsyncStopLogStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* SubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* AsyncSubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* PrepareAsyncSubscribeLogStreamingRawRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest& request, ::grpc::CompletionQueue* cq) override; + const ::grpc::internal::RpcMethod rpcmethod_StartLogStreaming_; + const ::grpc::internal::RpcMethod rpcmethod_StopLogStreaming_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeLogStreamingRaw_; + }; + 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(); + // Start streaming logging data. + virtual ::grpc::Status StartLogStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response); + // Stop streaming logging data. + virtual ::grpc::Status StopLogStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response); + // Subscribe to logging messages + virtual ::grpc::Status SubscribeLogStreamingRaw(::grpc::ServerContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* writer); + }; + template + class WithAsyncMethod_StartLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_StartLogStreaming() { + ::grpc::Service::MarkMethodAsync(0); + } + ~WithAsyncMethod_StartLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestStartLogStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>* 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_StopLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_StopLogStreaming() { + ::grpc::Service::MarkMethodAsync(1); + } + ~WithAsyncMethod_StopLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestStopLogStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* 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_SubscribeLogStreamingRaw : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeLogStreamingRaw() { + ::grpc::Service::MarkMethodAsync(2); + } + ~WithAsyncMethod_SubscribeLogStreamingRaw() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeLogStreamingRaw(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeLogStreamingRaw(::grpc::ServerContext* context, ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* 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); + } + }; + typedef WithAsyncMethod_StartLogStreaming > > AsyncService; + template + class WithCallbackMethod_StartLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_StartLogStreaming() { + ::grpc::Service::MarkMethodCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* response) { return this->StartLogStreaming(context, request, response); }));} + void SetMessageAllocatorFor_StartLogStreaming( + ::grpc::MessageAllocator< ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_StartLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* StartLogStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_StopLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_StopLogStreaming() { + ::grpc::Service::MarkMethodCallback(1, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* request, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* response) { return this->StopLogStreaming(context, request, response); }));} + void SetMessageAllocatorFor_StopLogStreaming( + ::grpc::MessageAllocator< ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_StopLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* StopLogStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeLogStreamingRaw : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeLogStreamingRaw() { + ::grpc::Service::MarkMethodCallback(2, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest, ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* request) { return this->SubscribeLogStreamingRaw(context, request); })); + } + ~WithCallbackMethod_SubscribeLogStreamingRaw() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeLogStreamingRaw(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* SubscribeLogStreamingRaw( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* /*request*/) { return nullptr; } + }; + typedef WithCallbackMethod_StartLogStreaming > > CallbackService; + typedef CallbackService ExperimentalCallbackService; + template + class WithGenericMethod_StartLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_StartLogStreaming() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_StartLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_StopLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_StopLogStreaming() { + ::grpc::Service::MarkMethodGeneric(1); + } + ~WithGenericMethod_StopLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeLogStreamingRaw : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeLogStreamingRaw() { + ::grpc::Service::MarkMethodGeneric(2); + } + ~WithGenericMethod_SubscribeLogStreamingRaw() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeLogStreamingRaw(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithRawMethod_StartLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_StartLogStreaming() { + ::grpc::Service::MarkMethodRaw(0); + } + ~WithRawMethod_StartLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestStartLogStreaming(::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_StopLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_StopLogStreaming() { + ::grpc::Service::MarkMethodRaw(1); + } + ~WithRawMethod_StopLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestStopLogStreaming(::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_SubscribeLogStreamingRaw : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeLogStreamingRaw() { + ::grpc::Service::MarkMethodRaw(2); + } + ~WithRawMethod_SubscribeLogStreamingRaw() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeLogStreamingRaw(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeLogStreamingRaw(::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 WithRawCallbackMethod_StartLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_StartLogStreaming() { + ::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->StartLogStreaming(context, request, response); })); + } + ~WithRawCallbackMethod_StartLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* StartLogStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_StopLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_StopLogStreaming() { + ::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->StopLogStreaming(context, request, response); })); + } + ~WithRawCallbackMethod_StopLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* StopLogStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeLogStreamingRaw : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeLogStreamingRaw() { + ::grpc::Service::MarkMethodRawCallback(2, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeLogStreamingRaw(context, request); })); + } + ~WithRawCallbackMethod_SubscribeLogStreamingRaw() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeLogStreamingRaw(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeLogStreamingRaw( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithStreamedUnaryMethod_StartLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_StartLogStreaming() { + ::grpc::Service::MarkMethodStreamed(0, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::log_streaming::StartLogStreamingRequest, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse>* streamer) { + return this->StreamedStartLogStreaming(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_StartLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status StartLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StartLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StartLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedStartLogStreaming(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::log_streaming::StartLogStreamingRequest,::mavsdk::rpc::log_streaming::StartLogStreamingResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_StopLogStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_StopLogStreaming() { + ::grpc::Service::MarkMethodStreamed(1, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::log_streaming::StopLogStreamingRequest, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* streamer) { + return this->StreamedStopLogStreaming(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_StopLogStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status StopLogStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::StopLogStreamingRequest* /*request*/, ::mavsdk::rpc::log_streaming::StopLogStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedStopLogStreaming(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::log_streaming::StopLogStreamingRequest,::mavsdk::rpc::log_streaming::StopLogStreamingResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_StartLogStreaming > StreamedUnaryService; + template + class WithSplitStreamingMethod_SubscribeLogStreamingRaw : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeLogStreamingRaw() { + ::grpc::Service::MarkMethodStreamed(2, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest, ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest, ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* streamer) { + return this->StreamedSubscribeLogStreamingRaw(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeLogStreamingRaw() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeLogStreamingRaw(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeLogStreamingRaw(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest,::mavsdk::rpc::log_streaming::LogStreamingRawResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeLogStreamingRaw SplitStreamedService; + typedef WithStreamedUnaryMethod_StartLogStreaming > > StreamedService; +}; + +} // namespace log_streaming +} // namespace rpc +} // namespace mavsdk + + +#endif // GRPC_log_5fstreaming_2flog_5fstreaming_2eproto__INCLUDED diff --git a/src/mavsdk_server/src/generated/log_streaming/log_streaming.pb.cc b/src/mavsdk_server/src/generated/log_streaming/log_streaming.pb.cc new file mode 100644 index 0000000000..444f54fb3c --- /dev/null +++ b/src/mavsdk_server/src/generated/log_streaming/log_streaming.pb.cc @@ -0,0 +1,1513 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: log_streaming/log_streaming.proto + +#include "log_streaming/log_streaming.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 log_streaming { + template +PROTOBUF_CONSTEXPR SubscribeLogStreamingRawRequest::SubscribeLogStreamingRawRequest(::_pbi::ConstantInitialized) {} +struct SubscribeLogStreamingRawRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeLogStreamingRawRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeLogStreamingRawRequestDefaultTypeInternal() {} + union { + SubscribeLogStreamingRawRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeLogStreamingRawRequestDefaultTypeInternal _SubscribeLogStreamingRawRequest_default_instance_; + template +PROTOBUF_CONSTEXPR StopLogStreamingRequest::StopLogStreamingRequest(::_pbi::ConstantInitialized) {} +struct StopLogStreamingRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR StopLogStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StopLogStreamingRequestDefaultTypeInternal() {} + union { + StopLogStreamingRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopLogStreamingRequestDefaultTypeInternal _StopLogStreamingRequest_default_instance_; + template +PROTOBUF_CONSTEXPR StartLogStreamingRequest::StartLogStreamingRequest(::_pbi::ConstantInitialized) {} +struct StartLogStreamingRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR StartLogStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StartLogStreamingRequestDefaultTypeInternal() {} + union { + StartLogStreamingRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartLogStreamingRequestDefaultTypeInternal _StartLogStreamingRequest_default_instance_; + +inline constexpr LogStreamingResult::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : result_str_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + result_{static_cast< ::mavsdk::rpc::log_streaming::LogStreamingResult_Result >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR LogStreamingResult::LogStreamingResult(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct LogStreamingResultDefaultTypeInternal { + PROTOBUF_CONSTEXPR LogStreamingResultDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~LogStreamingResultDefaultTypeInternal() {} + union { + LogStreamingResult _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 LogStreamingResultDefaultTypeInternal _LogStreamingResult_default_instance_; + +inline constexpr LogStreamingRaw::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : data_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR LogStreamingRaw::LogStreamingRaw(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct LogStreamingRawDefaultTypeInternal { + PROTOBUF_CONSTEXPR LogStreamingRawDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~LogStreamingRawDefaultTypeInternal() {} + union { + LogStreamingRaw _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 LogStreamingRawDefaultTypeInternal _LogStreamingRaw_default_instance_; + +inline constexpr StopLogStreamingResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + log_streaming_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR StopLogStreamingResponse::StopLogStreamingResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct StopLogStreamingResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR StopLogStreamingResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StopLogStreamingResponseDefaultTypeInternal() {} + union { + StopLogStreamingResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopLogStreamingResponseDefaultTypeInternal _StopLogStreamingResponse_default_instance_; + +inline constexpr StartLogStreamingResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + log_streaming_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR StartLogStreamingResponse::StartLogStreamingResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct StartLogStreamingResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR StartLogStreamingResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StartLogStreamingResponseDefaultTypeInternal() {} + union { + StartLogStreamingResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartLogStreamingResponseDefaultTypeInternal _StartLogStreamingResponse_default_instance_; + +inline constexpr LogStreamingRawResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + logging_raw_{nullptr} {} + +template +PROTOBUF_CONSTEXPR LogStreamingRawResponse::LogStreamingRawResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct LogStreamingRawResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR LogStreamingRawResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~LogStreamingRawResponseDefaultTypeInternal() {} + union { + LogStreamingRawResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 LogStreamingRawResponseDefaultTypeInternal _LogStreamingRawResponse_default_instance_; +} // namespace log_streaming +} // namespace rpc +} // namespace mavsdk +static ::_pb::Metadata file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[8]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_log_5fstreaming_2flog_5fstreaming_2eproto[1]; +static constexpr const ::_pb::ServiceDescriptor** + file_level_service_descriptors_log_5fstreaming_2flog_5fstreaming_2eproto = nullptr; +const ::uint32_t TableStruct_log_5fstreaming_2flog_5fstreaming_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( + protodesc_cold) = { + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::StartLogStreamingRequest, _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::log_streaming::StartLogStreamingResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::StartLogStreamingResponse, _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::log_streaming::StartLogStreamingResponse, _impl_.log_streaming_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::StopLogStreamingRequest, _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::log_streaming::StopLogStreamingResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::StopLogStreamingResponse, _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::log_streaming::StopLogStreamingResponse, _impl_.log_streaming_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest, _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::log_streaming::LogStreamingRawResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::LogStreamingRawResponse, _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::log_streaming::LogStreamingRawResponse, _impl_.logging_raw_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::LogStreamingRaw, _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::log_streaming::LogStreamingRaw, _impl_.data_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::LogStreamingResult, _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::log_streaming::LogStreamingResult, _impl_.result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_streaming::LogStreamingResult, _impl_.result_str_), +}; + +static const ::_pbi::MigrationSchema + schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + {0, -1, -1, sizeof(::mavsdk::rpc::log_streaming::StartLogStreamingRequest)}, + {8, 17, -1, sizeof(::mavsdk::rpc::log_streaming::StartLogStreamingResponse)}, + {18, -1, -1, sizeof(::mavsdk::rpc::log_streaming::StopLogStreamingRequest)}, + {26, 35, -1, sizeof(::mavsdk::rpc::log_streaming::StopLogStreamingResponse)}, + {36, -1, -1, sizeof(::mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest)}, + {44, 53, -1, sizeof(::mavsdk::rpc::log_streaming::LogStreamingRawResponse)}, + {54, -1, -1, sizeof(::mavsdk::rpc::log_streaming::LogStreamingRaw)}, + {63, -1, -1, sizeof(::mavsdk::rpc::log_streaming::LogStreamingResult)}, +}; + +static const ::_pb::Message* const file_default_instances[] = { + &::mavsdk::rpc::log_streaming::_StartLogStreamingRequest_default_instance_._instance, + &::mavsdk::rpc::log_streaming::_StartLogStreamingResponse_default_instance_._instance, + &::mavsdk::rpc::log_streaming::_StopLogStreamingRequest_default_instance_._instance, + &::mavsdk::rpc::log_streaming::_StopLogStreamingResponse_default_instance_._instance, + &::mavsdk::rpc::log_streaming::_SubscribeLogStreamingRawRequest_default_instance_._instance, + &::mavsdk::rpc::log_streaming::_LogStreamingRawResponse_default_instance_._instance, + &::mavsdk::rpc::log_streaming::_LogStreamingRaw_default_instance_._instance, + &::mavsdk::rpc::log_streaming::_LogStreamingResult_default_instance_._instance, +}; +const char descriptor_table_protodef_log_5fstreaming_2flog_5fstreaming_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + "\n!log_streaming/log_streaming.proto\022\030mav" + "sdk.rpc.log_streaming\032\024mavsdk_options.pr" + "oto\"\032\n\030StartLogStreamingRequest\"g\n\031Start" + "LogStreamingResponse\022J\n\024log_streaming_re" + "sult\030\001 \001(\0132,.mavsdk.rpc.log_streaming.Lo" + "gStreamingResult\"\031\n\027StopLogStreamingRequ" + "est\"f\n\030StopLogStreamingResponse\022J\n\024log_s" + "treaming_result\030\001 \001(\0132,.mavsdk.rpc.log_s" + "treaming.LogStreamingResult\"!\n\037Subscribe" + "LogStreamingRawRequest\"Y\n\027LogStreamingRa" + "wResponse\022>\n\013logging_raw\030\001 \001(\0132).mavsdk." + "rpc.log_streaming.LogStreamingRaw\"\037\n\017Log" + "StreamingRaw\022\014\n\004data\030\001 \001(\t\"\253\002\n\022LogStream" + "ingResult\022C\n\006result\030\001 \001(\01623.mavsdk.rpc.l" + "og_streaming.LogStreamingResult.Result\022\022" + "\n\nresult_str\030\002 \001(\t\"\273\001\n\006Result\022\022\n\016RESULT_" + "SUCCESS\020\000\022\024\n\020RESULT_NO_SYSTEM\020\001\022\033\n\027RESUL" + "T_CONNECTION_ERROR\020\002\022\017\n\013RESULT_BUSY\020\003\022\031\n" + "\025RESULT_COMMAND_DENIED\020\004\022\022\n\016RESULT_TIMEO" + "UT\020\005\022\026\n\022RESULT_UNSUPPORTED\020\006\022\022\n\016RESULT_U" + "NKNOWN\020\0072\245\003\n\023LogStreamingService\022~\n\021Star" + "tLogStreaming\0222.mavsdk.rpc.log_streaming" + ".StartLogStreamingRequest\0323.mavsdk.rpc.l" + "og_streaming.StartLogStreamingResponse\"\000" + "\022{\n\020StopLogStreaming\0221.mavsdk.rpc.log_st" + "reaming.StopLogStreamingRequest\0322.mavsdk" + ".rpc.log_streaming.StopLogStreamingRespo" + "nse\"\000\022\220\001\n\030SubscribeLogStreamingRaw\0229.mav" + "sdk.rpc.log_streaming.SubscribeLogStream" + "ingRawRequest\0321.mavsdk.rpc.log_streaming" + ".LogStreamingRawResponse\"\004\200\265\030\0000\001B,\n\027io.m" + "avsdk.log_streamingB\021LogStreamingProtob\006" + "proto3" +}; +static const ::_pbi::DescriptorTable* const descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_deps[1] = + { + &::descriptor_table_mavsdk_5foptions_2eproto, +}; +static ::absl::once_flag descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once; +const ::_pbi::DescriptorTable descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto = { + false, + false, + 1286, + descriptor_table_protodef_log_5fstreaming_2flog_5fstreaming_2eproto, + "log_streaming/log_streaming.proto", + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_deps, + 1, + 8, + schemas, + file_default_instances, + TableStruct_log_5fstreaming_2flog_5fstreaming_2eproto::offsets, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto, + file_level_enum_descriptors_log_5fstreaming_2flog_5fstreaming_2eproto, + file_level_service_descriptors_log_5fstreaming_2flog_5fstreaming_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_log_5fstreaming_2flog_5fstreaming_2eproto_getter() { + return &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto; +} +// Force running AddDescriptors() at dynamic initialization time. +PROTOBUF_ATTRIBUTE_INIT_PRIORITY2 +static ::_pbi::AddDescriptorsRunner dynamic_init_dummy_log_5fstreaming_2flog_5fstreaming_2eproto(&descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto); +namespace mavsdk { +namespace rpc { +namespace log_streaming { +const ::google::protobuf::EnumDescriptor* LogStreamingResult_Result_descriptor() { + ::google::protobuf::internal::AssignDescriptors(&descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto); + return file_level_enum_descriptors_log_5fstreaming_2flog_5fstreaming_2eproto[0]; +} +PROTOBUF_CONSTINIT const uint32_t LogStreamingResult_Result_internal_data_[] = { + 524288u, 0u, }; +bool LogStreamingResult_Result_IsValid(int value) { + return 0 <= value && value <= 7; +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr LogStreamingResult_Result LogStreamingResult::RESULT_SUCCESS; +constexpr LogStreamingResult_Result LogStreamingResult::RESULT_NO_SYSTEM; +constexpr LogStreamingResult_Result LogStreamingResult::RESULT_CONNECTION_ERROR; +constexpr LogStreamingResult_Result LogStreamingResult::RESULT_BUSY; +constexpr LogStreamingResult_Result LogStreamingResult::RESULT_COMMAND_DENIED; +constexpr LogStreamingResult_Result LogStreamingResult::RESULT_TIMEOUT; +constexpr LogStreamingResult_Result LogStreamingResult::RESULT_UNSUPPORTED; +constexpr LogStreamingResult_Result LogStreamingResult::RESULT_UNKNOWN; +constexpr LogStreamingResult_Result LogStreamingResult::Result_MIN; +constexpr LogStreamingResult_Result LogStreamingResult::Result_MAX; +constexpr int LogStreamingResult::Result_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +// =================================================================== + +class StartLogStreamingRequest::_Internal { + public: +}; + +StartLogStreamingRequest::StartLogStreamingRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_streaming.StartLogStreamingRequest) +} +StartLogStreamingRequest::StartLogStreamingRequest( + ::google::protobuf::Arena* arena, + const StartLogStreamingRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + StartLogStreamingRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_streaming.StartLogStreamingRequest) +} + + + + + + + + + +::google::protobuf::Metadata StartLogStreamingRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_getter, &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[0]); +} +// =================================================================== + +class StartLogStreamingResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(StartLogStreamingResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::log_streaming::LogStreamingResult& log_streaming_result(const StartLogStreamingResponse* msg); + static void set_has_log_streaming_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::log_streaming::LogStreamingResult& StartLogStreamingResponse::_Internal::log_streaming_result(const StartLogStreamingResponse* msg) { + return *msg->_impl_.log_streaming_result_; +} +StartLogStreamingResponse::StartLogStreamingResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_streaming.StartLogStreamingResponse) +} +inline PROTOBUF_NDEBUG_INLINE StartLogStreamingResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +StartLogStreamingResponse::StartLogStreamingResponse( + ::google::protobuf::Arena* arena, + const StartLogStreamingResponse& from) + : ::google::protobuf::Message(arena) { + StartLogStreamingResponse* 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_.log_streaming_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::log_streaming::LogStreamingResult>(arena, *from._impl_.log_streaming_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_streaming.StartLogStreamingResponse) +} +inline PROTOBUF_NDEBUG_INLINE StartLogStreamingResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void StartLogStreamingResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.log_streaming_result_ = {}; +} +StartLogStreamingResponse::~StartLogStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_streaming.StartLogStreamingResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void StartLogStreamingResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.log_streaming_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void StartLogStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_streaming.StartLogStreamingResponse) + 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_.log_streaming_result_ != nullptr); + _impl_.log_streaming_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* StartLogStreamingResponse::_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> StartLogStreamingResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(StartLogStreamingResponse, _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), + &_StartLogStreamingResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(StartLogStreamingResponse, _impl_.log_streaming_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; + {PROTOBUF_FIELD_OFFSET(StartLogStreamingResponse, _impl_.log_streaming_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::log_streaming::LogStreamingResult>()}, + }}, {{ + }}, +}; + +::uint8_t* StartLogStreamingResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_streaming.StartLogStreamingResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::log_streaming_result(this), + _Internal::log_streaming_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.log_streaming.StartLogStreamingResponse) + return target; +} + +::size_t StartLogStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_streaming.StartLogStreamingResponse) + ::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.log_streaming.LogStreamingResult log_streaming_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.log_streaming_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData StartLogStreamingResponse::_class_data_ = { + StartLogStreamingResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* StartLogStreamingResponse::GetClassData() const { + return &_class_data_; +} + +void StartLogStreamingResponse::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.log_streaming.StartLogStreamingResponse) + 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_log_streaming_result()->::mavsdk::rpc::log_streaming::LogStreamingResult::MergeFrom( + from._internal_log_streaming_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void StartLogStreamingResponse::CopyFrom(const StartLogStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_streaming.StartLogStreamingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool StartLogStreamingResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* StartLogStreamingResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void StartLogStreamingResponse::InternalSwap(StartLogStreamingResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.log_streaming_result_, other->_impl_.log_streaming_result_); +} + +::google::protobuf::Metadata StartLogStreamingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_getter, &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[1]); +} +// =================================================================== + +class StopLogStreamingRequest::_Internal { + public: +}; + +StopLogStreamingRequest::StopLogStreamingRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_streaming.StopLogStreamingRequest) +} +StopLogStreamingRequest::StopLogStreamingRequest( + ::google::protobuf::Arena* arena, + const StopLogStreamingRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + StopLogStreamingRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_streaming.StopLogStreamingRequest) +} + + + + + + + + + +::google::protobuf::Metadata StopLogStreamingRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_getter, &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[2]); +} +// =================================================================== + +class StopLogStreamingResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(StopLogStreamingResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::log_streaming::LogStreamingResult& log_streaming_result(const StopLogStreamingResponse* msg); + static void set_has_log_streaming_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::log_streaming::LogStreamingResult& StopLogStreamingResponse::_Internal::log_streaming_result(const StopLogStreamingResponse* msg) { + return *msg->_impl_.log_streaming_result_; +} +StopLogStreamingResponse::StopLogStreamingResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_streaming.StopLogStreamingResponse) +} +inline PROTOBUF_NDEBUG_INLINE StopLogStreamingResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +StopLogStreamingResponse::StopLogStreamingResponse( + ::google::protobuf::Arena* arena, + const StopLogStreamingResponse& from) + : ::google::protobuf::Message(arena) { + StopLogStreamingResponse* 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_.log_streaming_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::log_streaming::LogStreamingResult>(arena, *from._impl_.log_streaming_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_streaming.StopLogStreamingResponse) +} +inline PROTOBUF_NDEBUG_INLINE StopLogStreamingResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void StopLogStreamingResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.log_streaming_result_ = {}; +} +StopLogStreamingResponse::~StopLogStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_streaming.StopLogStreamingResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void StopLogStreamingResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.log_streaming_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void StopLogStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_streaming.StopLogStreamingResponse) + 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_.log_streaming_result_ != nullptr); + _impl_.log_streaming_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* StopLogStreamingResponse::_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> StopLogStreamingResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(StopLogStreamingResponse, _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), + &_StopLogStreamingResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(StopLogStreamingResponse, _impl_.log_streaming_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; + {PROTOBUF_FIELD_OFFSET(StopLogStreamingResponse, _impl_.log_streaming_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::log_streaming::LogStreamingResult>()}, + }}, {{ + }}, +}; + +::uint8_t* StopLogStreamingResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_streaming.StopLogStreamingResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::log_streaming_result(this), + _Internal::log_streaming_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.log_streaming.StopLogStreamingResponse) + return target; +} + +::size_t StopLogStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_streaming.StopLogStreamingResponse) + ::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.log_streaming.LogStreamingResult log_streaming_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.log_streaming_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData StopLogStreamingResponse::_class_data_ = { + StopLogStreamingResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* StopLogStreamingResponse::GetClassData() const { + return &_class_data_; +} + +void StopLogStreamingResponse::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.log_streaming.StopLogStreamingResponse) + 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_log_streaming_result()->::mavsdk::rpc::log_streaming::LogStreamingResult::MergeFrom( + from._internal_log_streaming_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void StopLogStreamingResponse::CopyFrom(const StopLogStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_streaming.StopLogStreamingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool StopLogStreamingResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* StopLogStreamingResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void StopLogStreamingResponse::InternalSwap(StopLogStreamingResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.log_streaming_result_, other->_impl_.log_streaming_result_); +} + +::google::protobuf::Metadata StopLogStreamingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_getter, &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[3]); +} +// =================================================================== + +class SubscribeLogStreamingRawRequest::_Internal { + public: +}; + +SubscribeLogStreamingRawRequest::SubscribeLogStreamingRawRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_streaming.SubscribeLogStreamingRawRequest) +} +SubscribeLogStreamingRawRequest::SubscribeLogStreamingRawRequest( + ::google::protobuf::Arena* arena, + const SubscribeLogStreamingRawRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeLogStreamingRawRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_streaming.SubscribeLogStreamingRawRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeLogStreamingRawRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_getter, &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[4]); +} +// =================================================================== + +class LogStreamingRawResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(LogStreamingRawResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::log_streaming::LogStreamingRaw& logging_raw(const LogStreamingRawResponse* msg); + static void set_has_logging_raw(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::log_streaming::LogStreamingRaw& LogStreamingRawResponse::_Internal::logging_raw(const LogStreamingRawResponse* msg) { + return *msg->_impl_.logging_raw_; +} +LogStreamingRawResponse::LogStreamingRawResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_streaming.LogStreamingRawResponse) +} +inline PROTOBUF_NDEBUG_INLINE LogStreamingRawResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +LogStreamingRawResponse::LogStreamingRawResponse( + ::google::protobuf::Arena* arena, + const LogStreamingRawResponse& from) + : ::google::protobuf::Message(arena) { + LogStreamingRawResponse* 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_.logging_raw_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::log_streaming::LogStreamingRaw>(arena, *from._impl_.logging_raw_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_streaming.LogStreamingRawResponse) +} +inline PROTOBUF_NDEBUG_INLINE LogStreamingRawResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void LogStreamingRawResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.logging_raw_ = {}; +} +LogStreamingRawResponse::~LogStreamingRawResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_streaming.LogStreamingRawResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void LogStreamingRawResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.logging_raw_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void LogStreamingRawResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_streaming.LogStreamingRawResponse) + 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_.logging_raw_ != nullptr); + _impl_.logging_raw_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* LogStreamingRawResponse::_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> LogStreamingRawResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(LogStreamingRawResponse, _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), + &_LogStreamingRawResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.log_streaming.LogStreamingRaw logging_raw = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(LogStreamingRawResponse, _impl_.logging_raw_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.log_streaming.LogStreamingRaw logging_raw = 1; + {PROTOBUF_FIELD_OFFSET(LogStreamingRawResponse, _impl_.logging_raw_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::log_streaming::LogStreamingRaw>()}, + }}, {{ + }}, +}; + +::uint8_t* LogStreamingRawResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_streaming.LogStreamingRawResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.log_streaming.LogStreamingRaw logging_raw = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::logging_raw(this), + _Internal::logging_raw(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.log_streaming.LogStreamingRawResponse) + return target; +} + +::size_t LogStreamingRawResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_streaming.LogStreamingRawResponse) + ::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.log_streaming.LogStreamingRaw logging_raw = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.logging_raw_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData LogStreamingRawResponse::_class_data_ = { + LogStreamingRawResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* LogStreamingRawResponse::GetClassData() const { + return &_class_data_; +} + +void LogStreamingRawResponse::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.log_streaming.LogStreamingRawResponse) + 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_logging_raw()->::mavsdk::rpc::log_streaming::LogStreamingRaw::MergeFrom( + from._internal_logging_raw()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void LogStreamingRawResponse::CopyFrom(const LogStreamingRawResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_streaming.LogStreamingRawResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool LogStreamingRawResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* LogStreamingRawResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void LogStreamingRawResponse::InternalSwap(LogStreamingRawResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.logging_raw_, other->_impl_.logging_raw_); +} + +::google::protobuf::Metadata LogStreamingRawResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_getter, &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[5]); +} +// =================================================================== + +class LogStreamingRaw::_Internal { + public: +}; + +LogStreamingRaw::LogStreamingRaw(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_streaming.LogStreamingRaw) +} +inline PROTOBUF_NDEBUG_INLINE LogStreamingRaw::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : data_(arena, from.data_), + _cached_size_{0} {} + +LogStreamingRaw::LogStreamingRaw( + ::google::protobuf::Arena* arena, + const LogStreamingRaw& from) + : ::google::protobuf::Message(arena) { + LogStreamingRaw* 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.log_streaming.LogStreamingRaw) +} +inline PROTOBUF_NDEBUG_INLINE LogStreamingRaw::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : data_(arena), + _cached_size_{0} {} + +inline void LogStreamingRaw::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); +} +LogStreamingRaw::~LogStreamingRaw() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_streaming.LogStreamingRaw) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void LogStreamingRaw::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.data_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void LogStreamingRaw::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_streaming.LogStreamingRaw) + 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_.data_.ClearToEmpty(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* LogStreamingRaw::_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, 53, 2> LogStreamingRaw::_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 + &_LogStreamingRaw_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // string data = 1; + {::_pbi::TcParser::FastUS1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(LogStreamingRaw, _impl_.data_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // string data = 1; + {PROTOBUF_FIELD_OFFSET(LogStreamingRaw, _impl_.data_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\50\4\0\0\0\0\0\0" + "mavsdk.rpc.log_streaming.LogStreamingRaw" + "data" + }}, +}; + +::uint8_t* LogStreamingRaw::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_streaming.LogStreamingRaw) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // string data = 1; + if (!this->_internal_data().empty()) { + const std::string& _s = this->_internal_data(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.log_streaming.LogStreamingRaw.data"); + 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.log_streaming.LogStreamingRaw) + return target; +} + +::size_t LogStreamingRaw::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_streaming.LogStreamingRaw) + ::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 data = 1; + if (!this->_internal_data().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_data()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData LogStreamingRaw::_class_data_ = { + LogStreamingRaw::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* LogStreamingRaw::GetClassData() const { + return &_class_data_; +} + +void LogStreamingRaw::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.log_streaming.LogStreamingRaw) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_data().empty()) { + _this->_internal_set_data(from._internal_data()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void LogStreamingRaw::CopyFrom(const LogStreamingRaw& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_streaming.LogStreamingRaw) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool LogStreamingRaw::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* LogStreamingRaw::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void LogStreamingRaw::InternalSwap(LogStreamingRaw* 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_.data_, &other->_impl_.data_, arena); +} + +::google::protobuf::Metadata LogStreamingRaw::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_getter, &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[6]); +} +// =================================================================== + +class LogStreamingResult::_Internal { + public: +}; + +LogStreamingResult::LogStreamingResult(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_streaming.LogStreamingResult) +} +inline PROTOBUF_NDEBUG_INLINE LogStreamingResult::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : result_str_(arena, from.result_str_), + _cached_size_{0} {} + +LogStreamingResult::LogStreamingResult( + ::google::protobuf::Arena* arena, + const LogStreamingResult& from) + : ::google::protobuf::Message(arena) { + LogStreamingResult* 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.log_streaming.LogStreamingResult) +} +inline PROTOBUF_NDEBUG_INLINE LogStreamingResult::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : result_str_(arena), + _cached_size_{0} {} + +inline void LogStreamingResult::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.result_ = {}; +} +LogStreamingResult::~LogStreamingResult() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_streaming.LogStreamingResult) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void LogStreamingResult::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.result_str_.Destroy(); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void LogStreamingResult::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_streaming.LogStreamingResult) + 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* LogStreamingResult::_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> LogStreamingResult::_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 + &_LogStreamingResult_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // string result_str = 2; + {::_pbi::TcParser::FastUS1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(LogStreamingResult, _impl_.result_str_)}}, + // .mavsdk.rpc.log_streaming.LogStreamingResult.Result result = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(LogStreamingResult, _impl_.result_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(LogStreamingResult, _impl_.result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.log_streaming.LogStreamingResult.Result result = 1; + {PROTOBUF_FIELD_OFFSET(LogStreamingResult, _impl_.result_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + // string result_str = 2; + {PROTOBUF_FIELD_OFFSET(LogStreamingResult, _impl_.result_str_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + }}, + // no aux_entries + {{ + "\53\0\12\0\0\0\0\0" + "mavsdk.rpc.log_streaming.LogStreamingResult" + "result_str" + }}, +}; + +::uint8_t* LogStreamingResult::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_streaming.LogStreamingResult) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // .mavsdk.rpc.log_streaming.LogStreamingResult.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.log_streaming.LogStreamingResult.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.log_streaming.LogStreamingResult) + return target; +} + +::size_t LogStreamingResult::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_streaming.LogStreamingResult) + ::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.log_streaming.LogStreamingResult.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 LogStreamingResult::_class_data_ = { + LogStreamingResult::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* LogStreamingResult::GetClassData() const { + return &_class_data_; +} + +void LogStreamingResult::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.log_streaming.LogStreamingResult) + 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 LogStreamingResult::CopyFrom(const LogStreamingResult& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_streaming.LogStreamingResult) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool LogStreamingResult::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* LogStreamingResult::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void LogStreamingResult::InternalSwap(LogStreamingResult* 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 LogStreamingResult::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_getter, &descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto_once, + file_level_metadata_log_5fstreaming_2flog_5fstreaming_2eproto[7]); +} +// @@protoc_insertion_point(namespace_scope) +} // namespace log_streaming +} // 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/log_streaming/log_streaming.pb.h b/src/mavsdk_server/src/generated/log_streaming/log_streaming.pb.h new file mode 100644 index 0000000000..77aa72cac4 --- /dev/null +++ b/src/mavsdk_server/src/generated/log_streaming/log_streaming.pb.h @@ -0,0 +1,1983 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: log_streaming/log_streaming.proto +// Protobuf C++ Version: 4.25.1 + +#ifndef GOOGLE_PROTOBUF_INCLUDED_log_5fstreaming_2flog_5fstreaming_2eproto_2epb_2eh +#define GOOGLE_PROTOBUF_INCLUDED_log_5fstreaming_2flog_5fstreaming_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_log_5fstreaming_2flog_5fstreaming_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_log_5fstreaming_2flog_5fstreaming_2eproto { + static const ::uint32_t offsets[]; +}; +extern const ::google::protobuf::internal::DescriptorTable + descriptor_table_log_5fstreaming_2flog_5fstreaming_2eproto; +namespace mavsdk { +namespace rpc { +namespace log_streaming { +class LogStreamingRaw; +struct LogStreamingRawDefaultTypeInternal; +extern LogStreamingRawDefaultTypeInternal _LogStreamingRaw_default_instance_; +class LogStreamingRawResponse; +struct LogStreamingRawResponseDefaultTypeInternal; +extern LogStreamingRawResponseDefaultTypeInternal _LogStreamingRawResponse_default_instance_; +class LogStreamingResult; +struct LogStreamingResultDefaultTypeInternal; +extern LogStreamingResultDefaultTypeInternal _LogStreamingResult_default_instance_; +class StartLogStreamingRequest; +struct StartLogStreamingRequestDefaultTypeInternal; +extern StartLogStreamingRequestDefaultTypeInternal _StartLogStreamingRequest_default_instance_; +class StartLogStreamingResponse; +struct StartLogStreamingResponseDefaultTypeInternal; +extern StartLogStreamingResponseDefaultTypeInternal _StartLogStreamingResponse_default_instance_; +class StopLogStreamingRequest; +struct StopLogStreamingRequestDefaultTypeInternal; +extern StopLogStreamingRequestDefaultTypeInternal _StopLogStreamingRequest_default_instance_; +class StopLogStreamingResponse; +struct StopLogStreamingResponseDefaultTypeInternal; +extern StopLogStreamingResponseDefaultTypeInternal _StopLogStreamingResponse_default_instance_; +class SubscribeLogStreamingRawRequest; +struct SubscribeLogStreamingRawRequestDefaultTypeInternal; +extern SubscribeLogStreamingRawRequestDefaultTypeInternal _SubscribeLogStreamingRawRequest_default_instance_; +} // namespace log_streaming +} // namespace rpc +} // namespace mavsdk +namespace google { +namespace protobuf { +} // namespace protobuf +} // namespace google + +namespace mavsdk { +namespace rpc { +namespace log_streaming { +enum LogStreamingResult_Result : int { + LogStreamingResult_Result_RESULT_SUCCESS = 0, + LogStreamingResult_Result_RESULT_NO_SYSTEM = 1, + LogStreamingResult_Result_RESULT_CONNECTION_ERROR = 2, + LogStreamingResult_Result_RESULT_BUSY = 3, + LogStreamingResult_Result_RESULT_COMMAND_DENIED = 4, + LogStreamingResult_Result_RESULT_TIMEOUT = 5, + LogStreamingResult_Result_RESULT_UNSUPPORTED = 6, + LogStreamingResult_Result_RESULT_UNKNOWN = 7, + LogStreamingResult_Result_LogStreamingResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + LogStreamingResult_Result_LogStreamingResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool LogStreamingResult_Result_IsValid(int value); +extern const uint32_t LogStreamingResult_Result_internal_data_[]; +constexpr LogStreamingResult_Result LogStreamingResult_Result_Result_MIN = static_cast(0); +constexpr LogStreamingResult_Result LogStreamingResult_Result_Result_MAX = static_cast(7); +constexpr int LogStreamingResult_Result_Result_ARRAYSIZE = 7 + 1; +const ::google::protobuf::EnumDescriptor* +LogStreamingResult_Result_descriptor(); +template +const std::string& LogStreamingResult_Result_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to Result_Name()."); + return LogStreamingResult_Result_Name(static_cast(value)); +} +template <> +inline const std::string& LogStreamingResult_Result_Name(LogStreamingResult_Result value) { + return ::google::protobuf::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool LogStreamingResult_Result_Parse(absl::string_view name, LogStreamingResult_Result* value) { + return ::google::protobuf::internal::ParseNamedEnum( + LogStreamingResult_Result_descriptor(), name, value); +} + +// =================================================================== + + +// ------------------------------------------------------------------- + +class SubscribeLogStreamingRawRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_streaming.SubscribeLogStreamingRawRequest) */ { + public: + inline SubscribeLogStreamingRawRequest() : SubscribeLogStreamingRawRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeLogStreamingRawRequest(::google::protobuf::internal::ConstantInitialized); + + inline SubscribeLogStreamingRawRequest(const SubscribeLogStreamingRawRequest& from) + : SubscribeLogStreamingRawRequest(nullptr, from) {} + SubscribeLogStreamingRawRequest(SubscribeLogStreamingRawRequest&& from) noexcept + : SubscribeLogStreamingRawRequest() { + *this = ::std::move(from); + } + + inline SubscribeLogStreamingRawRequest& operator=(const SubscribeLogStreamingRawRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeLogStreamingRawRequest& operator=(SubscribeLogStreamingRawRequest&& 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 SubscribeLogStreamingRawRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeLogStreamingRawRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeLogStreamingRawRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + friend void swap(SubscribeLogStreamingRawRequest& a, SubscribeLogStreamingRawRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeLogStreamingRawRequest* 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(SubscribeLogStreamingRawRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeLogStreamingRawRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeLogStreamingRawRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeLogStreamingRawRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.log_streaming.SubscribeLogStreamingRawRequest"; + } + protected: + explicit SubscribeLogStreamingRawRequest(::google::protobuf::Arena* arena); + SubscribeLogStreamingRawRequest(::google::protobuf::Arena* arena, const SubscribeLogStreamingRawRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_streaming.SubscribeLogStreamingRawRequest) + 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_log_5fstreaming_2flog_5fstreaming_2eproto; +};// ------------------------------------------------------------------- + +class StopLogStreamingRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_streaming.StopLogStreamingRequest) */ { + public: + inline StopLogStreamingRequest() : StopLogStreamingRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR StopLogStreamingRequest(::google::protobuf::internal::ConstantInitialized); + + inline StopLogStreamingRequest(const StopLogStreamingRequest& from) + : StopLogStreamingRequest(nullptr, from) {} + StopLogStreamingRequest(StopLogStreamingRequest&& from) noexcept + : StopLogStreamingRequest() { + *this = ::std::move(from); + } + + inline StopLogStreamingRequest& operator=(const StopLogStreamingRequest& from) { + CopyFrom(from); + return *this; + } + inline StopLogStreamingRequest& operator=(StopLogStreamingRequest&& 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 StopLogStreamingRequest& default_instance() { + return *internal_default_instance(); + } + static inline const StopLogStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_StopLogStreamingRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(StopLogStreamingRequest& a, StopLogStreamingRequest& b) { + a.Swap(&b); + } + inline void Swap(StopLogStreamingRequest* 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(StopLogStreamingRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StopLogStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const StopLogStreamingRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const StopLogStreamingRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.log_streaming.StopLogStreamingRequest"; + } + protected: + explicit StopLogStreamingRequest(::google::protobuf::Arena* arena); + StopLogStreamingRequest(::google::protobuf::Arena* arena, const StopLogStreamingRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_streaming.StopLogStreamingRequest) + 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_log_5fstreaming_2flog_5fstreaming_2eproto; +};// ------------------------------------------------------------------- + +class StartLogStreamingRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_streaming.StartLogStreamingRequest) */ { + public: + inline StartLogStreamingRequest() : StartLogStreamingRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR StartLogStreamingRequest(::google::protobuf::internal::ConstantInitialized); + + inline StartLogStreamingRequest(const StartLogStreamingRequest& from) + : StartLogStreamingRequest(nullptr, from) {} + StartLogStreamingRequest(StartLogStreamingRequest&& from) noexcept + : StartLogStreamingRequest() { + *this = ::std::move(from); + } + + inline StartLogStreamingRequest& operator=(const StartLogStreamingRequest& from) { + CopyFrom(from); + return *this; + } + inline StartLogStreamingRequest& operator=(StartLogStreamingRequest&& 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 StartLogStreamingRequest& default_instance() { + return *internal_default_instance(); + } + static inline const StartLogStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_StartLogStreamingRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + friend void swap(StartLogStreamingRequest& a, StartLogStreamingRequest& b) { + a.Swap(&b); + } + inline void Swap(StartLogStreamingRequest* 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(StartLogStreamingRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StartLogStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const StartLogStreamingRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const StartLogStreamingRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.log_streaming.StartLogStreamingRequest"; + } + protected: + explicit StartLogStreamingRequest(::google::protobuf::Arena* arena); + StartLogStreamingRequest(::google::protobuf::Arena* arena, const StartLogStreamingRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_streaming.StartLogStreamingRequest) + 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_log_5fstreaming_2flog_5fstreaming_2eproto; +};// ------------------------------------------------------------------- + +class LogStreamingResult final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_streaming.LogStreamingResult) */ { + public: + inline LogStreamingResult() : LogStreamingResult(nullptr) {} + ~LogStreamingResult() override; + template + explicit PROTOBUF_CONSTEXPR LogStreamingResult(::google::protobuf::internal::ConstantInitialized); + + inline LogStreamingResult(const LogStreamingResult& from) + : LogStreamingResult(nullptr, from) {} + LogStreamingResult(LogStreamingResult&& from) noexcept + : LogStreamingResult() { + *this = ::std::move(from); + } + + inline LogStreamingResult& operator=(const LogStreamingResult& from) { + CopyFrom(from); + return *this; + } + inline LogStreamingResult& operator=(LogStreamingResult&& 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 LogStreamingResult& default_instance() { + return *internal_default_instance(); + } + static inline const LogStreamingResult* internal_default_instance() { + return reinterpret_cast( + &_LogStreamingResult_default_instance_); + } + static constexpr int kIndexInFileMessages = + 7; + + friend void swap(LogStreamingResult& a, LogStreamingResult& b) { + a.Swap(&b); + } + inline void Swap(LogStreamingResult* 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(LogStreamingResult* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + LogStreamingResult* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const LogStreamingResult& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const LogStreamingResult& from) { + LogStreamingResult::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(LogStreamingResult* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.log_streaming.LogStreamingResult"; + } + protected: + explicit LogStreamingResult(::google::protobuf::Arena* arena); + LogStreamingResult(::google::protobuf::Arena* arena, const LogStreamingResult& 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 = LogStreamingResult_Result; + static constexpr Result RESULT_SUCCESS = LogStreamingResult_Result_RESULT_SUCCESS; + static constexpr Result RESULT_NO_SYSTEM = LogStreamingResult_Result_RESULT_NO_SYSTEM; + static constexpr Result RESULT_CONNECTION_ERROR = LogStreamingResult_Result_RESULT_CONNECTION_ERROR; + static constexpr Result RESULT_BUSY = LogStreamingResult_Result_RESULT_BUSY; + static constexpr Result RESULT_COMMAND_DENIED = LogStreamingResult_Result_RESULT_COMMAND_DENIED; + static constexpr Result RESULT_TIMEOUT = LogStreamingResult_Result_RESULT_TIMEOUT; + static constexpr Result RESULT_UNSUPPORTED = LogStreamingResult_Result_RESULT_UNSUPPORTED; + static constexpr Result RESULT_UNKNOWN = LogStreamingResult_Result_RESULT_UNKNOWN; + static inline bool Result_IsValid(int value) { + return LogStreamingResult_Result_IsValid(value); + } + static constexpr Result Result_MIN = LogStreamingResult_Result_Result_MIN; + static constexpr Result Result_MAX = LogStreamingResult_Result_Result_MAX; + static constexpr int Result_ARRAYSIZE = LogStreamingResult_Result_Result_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* Result_descriptor() { + return LogStreamingResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T value) { + return LogStreamingResult_Result_Name(value); + } + static inline bool Result_Parse(absl::string_view name, Result* value) { + return LogStreamingResult_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.log_streaming.LogStreamingResult.Result result = 1; + void clear_result() ; + ::mavsdk::rpc::log_streaming::LogStreamingResult_Result result() const; + void set_result(::mavsdk::rpc::log_streaming::LogStreamingResult_Result value); + + private: + ::mavsdk::rpc::log_streaming::LogStreamingResult_Result _internal_result() const; + void _internal_set_result(::mavsdk::rpc::log_streaming::LogStreamingResult_Result value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_streaming.LogStreamingResult) + 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 result_str_; + int result_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_log_5fstreaming_2flog_5fstreaming_2eproto; +};// ------------------------------------------------------------------- + +class LogStreamingRaw final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_streaming.LogStreamingRaw) */ { + public: + inline LogStreamingRaw() : LogStreamingRaw(nullptr) {} + ~LogStreamingRaw() override; + template + explicit PROTOBUF_CONSTEXPR LogStreamingRaw(::google::protobuf::internal::ConstantInitialized); + + inline LogStreamingRaw(const LogStreamingRaw& from) + : LogStreamingRaw(nullptr, from) {} + LogStreamingRaw(LogStreamingRaw&& from) noexcept + : LogStreamingRaw() { + *this = ::std::move(from); + } + + inline LogStreamingRaw& operator=(const LogStreamingRaw& from) { + CopyFrom(from); + return *this; + } + inline LogStreamingRaw& operator=(LogStreamingRaw&& 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 LogStreamingRaw& default_instance() { + return *internal_default_instance(); + } + static inline const LogStreamingRaw* internal_default_instance() { + return reinterpret_cast( + &_LogStreamingRaw_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + friend void swap(LogStreamingRaw& a, LogStreamingRaw& b) { + a.Swap(&b); + } + inline void Swap(LogStreamingRaw* 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(LogStreamingRaw* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + LogStreamingRaw* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const LogStreamingRaw& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const LogStreamingRaw& from) { + LogStreamingRaw::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(LogStreamingRaw* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.log_streaming.LogStreamingRaw"; + } + protected: + explicit LogStreamingRaw(::google::protobuf::Arena* arena); + LogStreamingRaw(::google::protobuf::Arena* arena, const LogStreamingRaw& 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, + }; + // string data = 1; + void clear_data() ; + const std::string& data() const; + template + void set_data(Arg_&& arg, Args_... args); + std::string* mutable_data(); + PROTOBUF_NODISCARD std::string* release_data(); + void set_allocated_data(std::string* value); + + private: + const std::string& _internal_data() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_data( + const std::string& value); + std::string* _internal_mutable_data(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_streaming.LogStreamingRaw) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 53, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::ArenaStringPtr data_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_log_5fstreaming_2flog_5fstreaming_2eproto; +};// ------------------------------------------------------------------- + +class StopLogStreamingResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_streaming.StopLogStreamingResponse) */ { + public: + inline StopLogStreamingResponse() : StopLogStreamingResponse(nullptr) {} + ~StopLogStreamingResponse() override; + template + explicit PROTOBUF_CONSTEXPR StopLogStreamingResponse(::google::protobuf::internal::ConstantInitialized); + + inline StopLogStreamingResponse(const StopLogStreamingResponse& from) + : StopLogStreamingResponse(nullptr, from) {} + StopLogStreamingResponse(StopLogStreamingResponse&& from) noexcept + : StopLogStreamingResponse() { + *this = ::std::move(from); + } + + inline StopLogStreamingResponse& operator=(const StopLogStreamingResponse& from) { + CopyFrom(from); + return *this; + } + inline StopLogStreamingResponse& operator=(StopLogStreamingResponse&& 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 StopLogStreamingResponse& default_instance() { + return *internal_default_instance(); + } + static inline const StopLogStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_StopLogStreamingResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + friend void swap(StopLogStreamingResponse& a, StopLogStreamingResponse& b) { + a.Swap(&b); + } + inline void Swap(StopLogStreamingResponse* 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(StopLogStreamingResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StopLogStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const StopLogStreamingResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const StopLogStreamingResponse& from) { + StopLogStreamingResponse::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(StopLogStreamingResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.log_streaming.StopLogStreamingResponse"; + } + protected: + explicit StopLogStreamingResponse(::google::protobuf::Arena* arena); + StopLogStreamingResponse(::google::protobuf::Arena* arena, const StopLogStreamingResponse& 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 { + kLogStreamingResultFieldNumber = 1, + }; + // .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; + bool has_log_streaming_result() const; + void clear_log_streaming_result() ; + const ::mavsdk::rpc::log_streaming::LogStreamingResult& log_streaming_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::log_streaming::LogStreamingResult* release_log_streaming_result(); + ::mavsdk::rpc::log_streaming::LogStreamingResult* mutable_log_streaming_result(); + void set_allocated_log_streaming_result(::mavsdk::rpc::log_streaming::LogStreamingResult* value); + void unsafe_arena_set_allocated_log_streaming_result(::mavsdk::rpc::log_streaming::LogStreamingResult* value); + ::mavsdk::rpc::log_streaming::LogStreamingResult* unsafe_arena_release_log_streaming_result(); + + private: + const ::mavsdk::rpc::log_streaming::LogStreamingResult& _internal_log_streaming_result() const; + ::mavsdk::rpc::log_streaming::LogStreamingResult* _internal_mutable_log_streaming_result(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_streaming.StopLogStreamingResponse) + 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::log_streaming::LogStreamingResult* log_streaming_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_log_5fstreaming_2flog_5fstreaming_2eproto; +};// ------------------------------------------------------------------- + +class StartLogStreamingResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_streaming.StartLogStreamingResponse) */ { + public: + inline StartLogStreamingResponse() : StartLogStreamingResponse(nullptr) {} + ~StartLogStreamingResponse() override; + template + explicit PROTOBUF_CONSTEXPR StartLogStreamingResponse(::google::protobuf::internal::ConstantInitialized); + + inline StartLogStreamingResponse(const StartLogStreamingResponse& from) + : StartLogStreamingResponse(nullptr, from) {} + StartLogStreamingResponse(StartLogStreamingResponse&& from) noexcept + : StartLogStreamingResponse() { + *this = ::std::move(from); + } + + inline StartLogStreamingResponse& operator=(const StartLogStreamingResponse& from) { + CopyFrom(from); + return *this; + } + inline StartLogStreamingResponse& operator=(StartLogStreamingResponse&& 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 StartLogStreamingResponse& default_instance() { + return *internal_default_instance(); + } + static inline const StartLogStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_StartLogStreamingResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + friend void swap(StartLogStreamingResponse& a, StartLogStreamingResponse& b) { + a.Swap(&b); + } + inline void Swap(StartLogStreamingResponse* 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(StartLogStreamingResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StartLogStreamingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const StartLogStreamingResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const StartLogStreamingResponse& from) { + StartLogStreamingResponse::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(StartLogStreamingResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.log_streaming.StartLogStreamingResponse"; + } + protected: + explicit StartLogStreamingResponse(::google::protobuf::Arena* arena); + StartLogStreamingResponse(::google::protobuf::Arena* arena, const StartLogStreamingResponse& 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 { + kLogStreamingResultFieldNumber = 1, + }; + // .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; + bool has_log_streaming_result() const; + void clear_log_streaming_result() ; + const ::mavsdk::rpc::log_streaming::LogStreamingResult& log_streaming_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::log_streaming::LogStreamingResult* release_log_streaming_result(); + ::mavsdk::rpc::log_streaming::LogStreamingResult* mutable_log_streaming_result(); + void set_allocated_log_streaming_result(::mavsdk::rpc::log_streaming::LogStreamingResult* value); + void unsafe_arena_set_allocated_log_streaming_result(::mavsdk::rpc::log_streaming::LogStreamingResult* value); + ::mavsdk::rpc::log_streaming::LogStreamingResult* unsafe_arena_release_log_streaming_result(); + + private: + const ::mavsdk::rpc::log_streaming::LogStreamingResult& _internal_log_streaming_result() const; + ::mavsdk::rpc::log_streaming::LogStreamingResult* _internal_mutable_log_streaming_result(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_streaming.StartLogStreamingResponse) + 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::log_streaming::LogStreamingResult* log_streaming_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_log_5fstreaming_2flog_5fstreaming_2eproto; +};// ------------------------------------------------------------------- + +class LogStreamingRawResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_streaming.LogStreamingRawResponse) */ { + public: + inline LogStreamingRawResponse() : LogStreamingRawResponse(nullptr) {} + ~LogStreamingRawResponse() override; + template + explicit PROTOBUF_CONSTEXPR LogStreamingRawResponse(::google::protobuf::internal::ConstantInitialized); + + inline LogStreamingRawResponse(const LogStreamingRawResponse& from) + : LogStreamingRawResponse(nullptr, from) {} + LogStreamingRawResponse(LogStreamingRawResponse&& from) noexcept + : LogStreamingRawResponse() { + *this = ::std::move(from); + } + + inline LogStreamingRawResponse& operator=(const LogStreamingRawResponse& from) { + CopyFrom(from); + return *this; + } + inline LogStreamingRawResponse& operator=(LogStreamingRawResponse&& 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 LogStreamingRawResponse& default_instance() { + return *internal_default_instance(); + } + static inline const LogStreamingRawResponse* internal_default_instance() { + return reinterpret_cast( + &_LogStreamingRawResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + friend void swap(LogStreamingRawResponse& a, LogStreamingRawResponse& b) { + a.Swap(&b); + } + inline void Swap(LogStreamingRawResponse* 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(LogStreamingRawResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + LogStreamingRawResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const LogStreamingRawResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const LogStreamingRawResponse& from) { + LogStreamingRawResponse::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(LogStreamingRawResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.log_streaming.LogStreamingRawResponse"; + } + protected: + explicit LogStreamingRawResponse(::google::protobuf::Arena* arena); + LogStreamingRawResponse(::google::protobuf::Arena* arena, const LogStreamingRawResponse& 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 { + kLoggingRawFieldNumber = 1, + }; + // .mavsdk.rpc.log_streaming.LogStreamingRaw logging_raw = 1; + bool has_logging_raw() const; + void clear_logging_raw() ; + const ::mavsdk::rpc::log_streaming::LogStreamingRaw& logging_raw() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::log_streaming::LogStreamingRaw* release_logging_raw(); + ::mavsdk::rpc::log_streaming::LogStreamingRaw* mutable_logging_raw(); + void set_allocated_logging_raw(::mavsdk::rpc::log_streaming::LogStreamingRaw* value); + void unsafe_arena_set_allocated_logging_raw(::mavsdk::rpc::log_streaming::LogStreamingRaw* value); + ::mavsdk::rpc::log_streaming::LogStreamingRaw* unsafe_arena_release_logging_raw(); + + private: + const ::mavsdk::rpc::log_streaming::LogStreamingRaw& _internal_logging_raw() const; + ::mavsdk::rpc::log_streaming::LogStreamingRaw* _internal_mutable_logging_raw(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_streaming.LogStreamingRawResponse) + 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::log_streaming::LogStreamingRaw* logging_raw_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_log_5fstreaming_2flog_5fstreaming_2eproto; +}; + +// =================================================================== + + + + +// =================================================================== + + +#ifdef __GNUC__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// StartLogStreamingRequest + +// ------------------------------------------------------------------- + +// StartLogStreamingResponse + +// .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; +inline bool StartLogStreamingResponse::has_log_streaming_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.log_streaming_result_ != nullptr); + return value; +} +inline void StartLogStreamingResponse::clear_log_streaming_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.log_streaming_result_ != nullptr) _impl_.log_streaming_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::log_streaming::LogStreamingResult& StartLogStreamingResponse::_internal_log_streaming_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::log_streaming::LogStreamingResult* p = _impl_.log_streaming_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::log_streaming::_LogStreamingResult_default_instance_); +} +inline const ::mavsdk::rpc::log_streaming::LogStreamingResult& StartLogStreamingResponse::log_streaming_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_streaming.StartLogStreamingResponse.log_streaming_result) + return _internal_log_streaming_result(); +} +inline void StartLogStreamingResponse::unsafe_arena_set_allocated_log_streaming_result(::mavsdk::rpc::log_streaming::LogStreamingResult* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.log_streaming_result_); + } + _impl_.log_streaming_result_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(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.log_streaming.StartLogStreamingResponse.log_streaming_result) +} +inline ::mavsdk::rpc::log_streaming::LogStreamingResult* StartLogStreamingResponse::release_log_streaming_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::log_streaming::LogStreamingResult* released = _impl_.log_streaming_result_; + _impl_.log_streaming_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::log_streaming::LogStreamingResult* StartLogStreamingResponse::unsafe_arena_release_log_streaming_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.log_streaming.StartLogStreamingResponse.log_streaming_result) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::log_streaming::LogStreamingResult* temp = _impl_.log_streaming_result_; + _impl_.log_streaming_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::log_streaming::LogStreamingResult* StartLogStreamingResponse::_internal_mutable_log_streaming_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.log_streaming_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::log_streaming::LogStreamingResult>(GetArena()); + _impl_.log_streaming_result_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(p); + } + return _impl_.log_streaming_result_; +} +inline ::mavsdk::rpc::log_streaming::LogStreamingResult* StartLogStreamingResponse::mutable_log_streaming_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::log_streaming::LogStreamingResult* _msg = _internal_mutable_log_streaming_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.log_streaming.StartLogStreamingResponse.log_streaming_result) + return _msg; +} +inline void StartLogStreamingResponse::set_allocated_log_streaming_result(::mavsdk::rpc::log_streaming::LogStreamingResult* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(_impl_.log_streaming_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(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_.log_streaming_result_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.log_streaming.StartLogStreamingResponse.log_streaming_result) +} + +// ------------------------------------------------------------------- + +// StopLogStreamingRequest + +// ------------------------------------------------------------------- + +// StopLogStreamingResponse + +// .mavsdk.rpc.log_streaming.LogStreamingResult log_streaming_result = 1; +inline bool StopLogStreamingResponse::has_log_streaming_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.log_streaming_result_ != nullptr); + return value; +} +inline void StopLogStreamingResponse::clear_log_streaming_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.log_streaming_result_ != nullptr) _impl_.log_streaming_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::log_streaming::LogStreamingResult& StopLogStreamingResponse::_internal_log_streaming_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::log_streaming::LogStreamingResult* p = _impl_.log_streaming_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::log_streaming::_LogStreamingResult_default_instance_); +} +inline const ::mavsdk::rpc::log_streaming::LogStreamingResult& StopLogStreamingResponse::log_streaming_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_streaming.StopLogStreamingResponse.log_streaming_result) + return _internal_log_streaming_result(); +} +inline void StopLogStreamingResponse::unsafe_arena_set_allocated_log_streaming_result(::mavsdk::rpc::log_streaming::LogStreamingResult* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.log_streaming_result_); + } + _impl_.log_streaming_result_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(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.log_streaming.StopLogStreamingResponse.log_streaming_result) +} +inline ::mavsdk::rpc::log_streaming::LogStreamingResult* StopLogStreamingResponse::release_log_streaming_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::log_streaming::LogStreamingResult* released = _impl_.log_streaming_result_; + _impl_.log_streaming_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::log_streaming::LogStreamingResult* StopLogStreamingResponse::unsafe_arena_release_log_streaming_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.log_streaming.StopLogStreamingResponse.log_streaming_result) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::log_streaming::LogStreamingResult* temp = _impl_.log_streaming_result_; + _impl_.log_streaming_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::log_streaming::LogStreamingResult* StopLogStreamingResponse::_internal_mutable_log_streaming_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.log_streaming_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::log_streaming::LogStreamingResult>(GetArena()); + _impl_.log_streaming_result_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(p); + } + return _impl_.log_streaming_result_; +} +inline ::mavsdk::rpc::log_streaming::LogStreamingResult* StopLogStreamingResponse::mutable_log_streaming_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::log_streaming::LogStreamingResult* _msg = _internal_mutable_log_streaming_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.log_streaming.StopLogStreamingResponse.log_streaming_result) + return _msg; +} +inline void StopLogStreamingResponse::set_allocated_log_streaming_result(::mavsdk::rpc::log_streaming::LogStreamingResult* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(_impl_.log_streaming_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(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_.log_streaming_result_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.log_streaming.StopLogStreamingResponse.log_streaming_result) +} + +// ------------------------------------------------------------------- + +// SubscribeLogStreamingRawRequest + +// ------------------------------------------------------------------- + +// LogStreamingRawResponse + +// .mavsdk.rpc.log_streaming.LogStreamingRaw logging_raw = 1; +inline bool LogStreamingRawResponse::has_logging_raw() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.logging_raw_ != nullptr); + return value; +} +inline void LogStreamingRawResponse::clear_logging_raw() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.logging_raw_ != nullptr) _impl_.logging_raw_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::log_streaming::LogStreamingRaw& LogStreamingRawResponse::_internal_logging_raw() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::log_streaming::LogStreamingRaw* p = _impl_.logging_raw_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::log_streaming::_LogStreamingRaw_default_instance_); +} +inline const ::mavsdk::rpc::log_streaming::LogStreamingRaw& LogStreamingRawResponse::logging_raw() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_streaming.LogStreamingRawResponse.logging_raw) + return _internal_logging_raw(); +} +inline void LogStreamingRawResponse::unsafe_arena_set_allocated_logging_raw(::mavsdk::rpc::log_streaming::LogStreamingRaw* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.logging_raw_); + } + _impl_.logging_raw_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingRaw*>(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.log_streaming.LogStreamingRawResponse.logging_raw) +} +inline ::mavsdk::rpc::log_streaming::LogStreamingRaw* LogStreamingRawResponse::release_logging_raw() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::log_streaming::LogStreamingRaw* released = _impl_.logging_raw_; + _impl_.logging_raw_ = 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::log_streaming::LogStreamingRaw* LogStreamingRawResponse::unsafe_arena_release_logging_raw() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.log_streaming.LogStreamingRawResponse.logging_raw) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::log_streaming::LogStreamingRaw* temp = _impl_.logging_raw_; + _impl_.logging_raw_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::log_streaming::LogStreamingRaw* LogStreamingRawResponse::_internal_mutable_logging_raw() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.logging_raw_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::log_streaming::LogStreamingRaw>(GetArena()); + _impl_.logging_raw_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingRaw*>(p); + } + return _impl_.logging_raw_; +} +inline ::mavsdk::rpc::log_streaming::LogStreamingRaw* LogStreamingRawResponse::mutable_logging_raw() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::log_streaming::LogStreamingRaw* _msg = _internal_mutable_logging_raw(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.log_streaming.LogStreamingRawResponse.logging_raw) + return _msg; +} +inline void LogStreamingRawResponse::set_allocated_logging_raw(::mavsdk::rpc::log_streaming::LogStreamingRaw* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingRaw*>(_impl_.logging_raw_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingRaw*>(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_.logging_raw_ = reinterpret_cast<::mavsdk::rpc::log_streaming::LogStreamingRaw*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.log_streaming.LogStreamingRawResponse.logging_raw) +} + +// ------------------------------------------------------------------- + +// LogStreamingRaw + +// string data = 1; +inline void LogStreamingRaw::clear_data() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.data_.ClearToEmpty(); +} +inline const std::string& LogStreamingRaw::data() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_streaming.LogStreamingRaw.data) + return _internal_data(); +} +template +inline PROTOBUF_ALWAYS_INLINE void LogStreamingRaw::set_data(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.data_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.log_streaming.LogStreamingRaw.data) +} +inline std::string* LogStreamingRaw::mutable_data() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_data(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.log_streaming.LogStreamingRaw.data) + return _s; +} +inline const std::string& LogStreamingRaw::_internal_data() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.data_.Get(); +} +inline void LogStreamingRaw::_internal_set_data(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.data_.Set(value, GetArena()); +} +inline std::string* LogStreamingRaw::_internal_mutable_data() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.data_.Mutable( GetArena()); +} +inline std::string* LogStreamingRaw::release_data() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.log_streaming.LogStreamingRaw.data) + return _impl_.data_.Release(); +} +inline void LogStreamingRaw::set_allocated_data(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.data_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.data_.IsDefault()) { + _impl_.data_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.log_streaming.LogStreamingRaw.data) +} + +// ------------------------------------------------------------------- + +// LogStreamingResult + +// .mavsdk.rpc.log_streaming.LogStreamingResult.Result result = 1; +inline void LogStreamingResult::clear_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.result_ = 0; +} +inline ::mavsdk::rpc::log_streaming::LogStreamingResult_Result LogStreamingResult::result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_streaming.LogStreamingResult.result) + return _internal_result(); +} +inline void LogStreamingResult::set_result(::mavsdk::rpc::log_streaming::LogStreamingResult_Result value) { + _internal_set_result(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.log_streaming.LogStreamingResult.result) +} +inline ::mavsdk::rpc::log_streaming::LogStreamingResult_Result LogStreamingResult::_internal_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return static_cast<::mavsdk::rpc::log_streaming::LogStreamingResult_Result>(_impl_.result_); +} +inline void LogStreamingResult::_internal_set_result(::mavsdk::rpc::log_streaming::LogStreamingResult_Result value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.result_ = value; +} + +// string result_str = 2; +inline void LogStreamingResult::clear_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.result_str_.ClearToEmpty(); +} +inline const std::string& LogStreamingResult::result_str() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_streaming.LogStreamingResult.result_str) + return _internal_result_str(); +} +template +inline PROTOBUF_ALWAYS_INLINE void LogStreamingResult::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.log_streaming.LogStreamingResult.result_str) +} +inline std::string* LogStreamingResult::mutable_result_str() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_result_str(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.log_streaming.LogStreamingResult.result_str) + return _s; +} +inline const std::string& LogStreamingResult::_internal_result_str() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.result_str_.Get(); +} +inline void LogStreamingResult::_internal_set_result_str(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.result_str_.Set(value, GetArena()); +} +inline std::string* LogStreamingResult::_internal_mutable_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.result_str_.Mutable( GetArena()); +} +inline std::string* LogStreamingResult::release_result_str() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.log_streaming.LogStreamingResult.result_str) + return _impl_.result_str_.Release(); +} +inline void LogStreamingResult::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.log_streaming.LogStreamingResult.result_str) +} + +#ifdef __GNUC__ +#pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) +} // namespace log_streaming +} // namespace rpc +} // namespace mavsdk + + +namespace google { +namespace protobuf { + +template <> +struct is_proto_enum<::mavsdk::rpc::log_streaming::LogStreamingResult_Result> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::log_streaming::LogStreamingResult_Result>() { + return ::mavsdk::rpc::log_streaming::LogStreamingResult_Result_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#include "google/protobuf/port_undef.inc" + +#endif // GOOGLE_PROTOBUF_INCLUDED_log_5fstreaming_2flog_5fstreaming_2eproto_2epb_2eh diff --git a/src/mavsdk_server/src/grpc_server.cpp b/src/mavsdk_server/src/grpc_server.cpp index f7aa97999c..5e964e636a 100644 --- a/src/mavsdk_server/src/grpc_server.cpp +++ b/src/mavsdk_server/src/grpc_server.cpp @@ -90,6 +90,10 @@ int GrpcServer::run() builder.RegisterService(&_log_files_service); #endif +#ifdef LOG_STREAMING_ENABLED + builder.RegisterService(&_log_streaming_service); +#endif + #ifdef MANUAL_CONTROL_ENABLED builder.RegisterService(&_manual_control_service); #endif @@ -253,6 +257,10 @@ void GrpcServer::stop() _log_files_service.stop(); #endif +#ifdef LOG_STREAMING_ENABLED + _log_streaming_service.stop(); +#endif + #ifdef MANUAL_CONTROL_ENABLED _manual_control_service.stop(); #endif diff --git a/src/mavsdk_server/src/grpc_server.h b/src/mavsdk_server/src/grpc_server.h index 47032aa171..bf4af946e3 100644 --- a/src/mavsdk_server/src/grpc_server.h +++ b/src/mavsdk_server/src/grpc_server.h @@ -99,6 +99,11 @@ #include "log_files/log_files_service_impl.h" #endif +#ifdef LOG_STREAMING_ENABLED +#include "plugins/log_streaming/log_streaming.h" +#include "log_streaming/log_streaming_service_impl.h" +#endif + #ifdef MANUAL_CONTROL_ENABLED #include "plugins/manual_control/manual_control.h" #include "manual_control/manual_control_service_impl.h" @@ -272,6 +277,11 @@ class GrpcServer { _log_files_service(_log_files_lazy_plugin), #endif +#ifdef LOG_STREAMING_ENABLED + _log_streaming_lazy_plugin(mavsdk), + _log_streaming_service(_log_streaming_lazy_plugin), +#endif + #ifdef MANUAL_CONTROL_ENABLED _manual_control_lazy_plugin(mavsdk), _manual_control_service(_manual_control_lazy_plugin), @@ -483,6 +493,13 @@ class GrpcServer { LogFilesServiceImpl<> _log_files_service; #endif +#ifdef LOG_STREAMING_ENABLED + + LazyPlugin _log_streaming_lazy_plugin; + + LogStreamingServiceImpl<> _log_streaming_service; +#endif + #ifdef MANUAL_CONTROL_ENABLED LazyPlugin _manual_control_lazy_plugin; diff --git a/src/mavsdk_server/src/plugins/log_streaming/log_streaming_service_impl.h b/src/mavsdk_server/src/plugins/log_streaming/log_streaming_service_impl.h new file mode 100644 index 0000000000..e60aa80e78 --- /dev/null +++ b/src/mavsdk_server/src/plugins/log_streaming/log_streaming_service_impl.h @@ -0,0 +1,247 @@ +// 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/log_streaming/log_streaming.proto) + +#include "log_streaming/log_streaming.grpc.pb.h" +#include "plugins/log_streaming/log_streaming.h" + +#include "mavsdk.h" + +#include "lazy_plugin.h" + +#include "log.h" +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace mavsdk_server { + +template> + +class LogStreamingServiceImpl final : public rpc::log_streaming::LogStreamingService::Service { +public: + LogStreamingServiceImpl(LazyPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) {} + + template + void fillResponseWithResult(ResponseType* response, mavsdk::LogStreaming::Result& result) const + { + auto rpc_result = translateToRpcResult(result); + + auto* rpc_log_streaming_result = new rpc::log_streaming::LogStreamingResult(); + rpc_log_streaming_result->set_result(rpc_result); + std::stringstream ss; + ss << result; + rpc_log_streaming_result->set_result_str(ss.str()); + + response->set_allocated_log_streaming_result(rpc_log_streaming_result); + } + + static std::unique_ptr + translateToRpcLogStreamingRaw(const mavsdk::LogStreaming::LogStreamingRaw& log_streaming_raw) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_data(log_streaming_raw.data); + + return rpc_obj; + } + + static mavsdk::LogStreaming::LogStreamingRaw + translateFromRpcLogStreamingRaw(const rpc::log_streaming::LogStreamingRaw& log_streaming_raw) + { + mavsdk::LogStreaming::LogStreamingRaw obj; + + obj.data = log_streaming_raw.data(); + + return obj; + } + + static rpc::log_streaming::LogStreamingResult::Result + translateToRpcResult(const mavsdk::LogStreaming::Result& result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case mavsdk::LogStreaming::Result::Success: + return rpc::log_streaming::LogStreamingResult_Result_RESULT_SUCCESS; + case mavsdk::LogStreaming::Result::NoSystem: + return rpc::log_streaming::LogStreamingResult_Result_RESULT_NO_SYSTEM; + case mavsdk::LogStreaming::Result::ConnectionError: + return rpc::log_streaming::LogStreamingResult_Result_RESULT_CONNECTION_ERROR; + case mavsdk::LogStreaming::Result::Busy: + return rpc::log_streaming::LogStreamingResult_Result_RESULT_BUSY; + case mavsdk::LogStreaming::Result::CommandDenied: + return rpc::log_streaming::LogStreamingResult_Result_RESULT_COMMAND_DENIED; + case mavsdk::LogStreaming::Result::Timeout: + return rpc::log_streaming::LogStreamingResult_Result_RESULT_TIMEOUT; + case mavsdk::LogStreaming::Result::Unsupported: + return rpc::log_streaming::LogStreamingResult_Result_RESULT_UNSUPPORTED; + case mavsdk::LogStreaming::Result::Unknown: + return rpc::log_streaming::LogStreamingResult_Result_RESULT_UNKNOWN; + } + } + + static mavsdk::LogStreaming::Result + translateFromRpcResult(const rpc::log_streaming::LogStreamingResult::Result result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case rpc::log_streaming::LogStreamingResult_Result_RESULT_SUCCESS: + return mavsdk::LogStreaming::Result::Success; + case rpc::log_streaming::LogStreamingResult_Result_RESULT_NO_SYSTEM: + return mavsdk::LogStreaming::Result::NoSystem; + case rpc::log_streaming::LogStreamingResult_Result_RESULT_CONNECTION_ERROR: + return mavsdk::LogStreaming::Result::ConnectionError; + case rpc::log_streaming::LogStreamingResult_Result_RESULT_BUSY: + return mavsdk::LogStreaming::Result::Busy; + case rpc::log_streaming::LogStreamingResult_Result_RESULT_COMMAND_DENIED: + return mavsdk::LogStreaming::Result::CommandDenied; + case rpc::log_streaming::LogStreamingResult_Result_RESULT_TIMEOUT: + return mavsdk::LogStreaming::Result::Timeout; + case rpc::log_streaming::LogStreamingResult_Result_RESULT_UNSUPPORTED: + return mavsdk::LogStreaming::Result::Unsupported; + case rpc::log_streaming::LogStreamingResult_Result_RESULT_UNKNOWN: + return mavsdk::LogStreaming::Result::Unknown; + } + } + + grpc::Status StartLogStreaming( + grpc::ServerContext* /* context */, + const rpc::log_streaming::StartLogStreamingRequest* /* request */, + rpc::log_streaming::StartLogStreamingResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::LogStreaming::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->start_log_streaming(); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status StopLogStreaming( + grpc::ServerContext* /* context */, + const rpc::log_streaming::StopLogStreamingRequest* /* request */, + rpc::log_streaming::StopLogStreamingResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::LogStreaming::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->stop_log_streaming(); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status SubscribeLogStreamingRaw( + grpc::ServerContext* /* context */, + const mavsdk::rpc::log_streaming::SubscribeLogStreamingRawRequest* /* 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::LogStreaming::LogStreamingRawHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_log_streaming_raw( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::LogStreaming::LogStreamingRaw log_streaming_raw) { + rpc::log_streaming::LogStreamingRawResponse rpc_response; + + rpc_response.set_allocated_logging_raw( + translateToRpcLogStreamingRaw(log_streaming_raw).release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_log_streaming_raw(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/plugins.txt b/src/plugins.txt index cf044cdb38..651b5613c9 100644 --- a/src/plugins.txt +++ b/src/plugins.txt @@ -15,6 +15,7 @@ gimbal gripper info log_files +log_streaming manual_control mission mission_raw