diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 9b12c2b171..c1539c9840 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -21,6 +21,7 @@ add_subdirectory(ftp_server) add_subdirectory(geofence_inclusion) add_subdirectory(gimbal) add_subdirectory(gimbal_device_tester) +add_subdirectory(logfile_download) add_subdirectory(manual_control) add_subdirectory(mavshell) add_subdirectory(multiple_drones) diff --git a/examples/logfile_download/CMakeLists.txt b/examples/logfile_download/CMakeLists.txt new file mode 100644 index 0000000000..4933734c2f --- /dev/null +++ b/examples/logfile_download/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(logfile_download) + +add_executable(logfile_download + logfile_download.cpp +) + +find_package(MAVSDK REQUIRED) + +target_link_libraries(logfile_download + MAVSDK::mavsdk +) + +if(NOT MSVC) + add_compile_options(logfile_download PRIVATE -Wall -Wextra) +else() + add_compile_options(logfile_download PRIVATE -WX -W2) +endif() diff --git a/examples/logfile_download/logfile_download.cpp b/examples/logfile_download/logfile_download.cpp new file mode 100644 index 0000000000..acbe781083 --- /dev/null +++ b/examples/logfile_download/logfile_download.cpp @@ -0,0 +1,122 @@ +// +// Example how to download logfiles 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\n" + << '\n' + << "To remove log files after all downloads completed,\n" + << "please add the --rm argument" << std::endl; +} + +std::shared_ptr get_system(Mavsdk& mavsdk) +{ + std::cerr << "Waiting to discover system...\n"; + auto prom = std::promise>{}; + auto fut = prom.get_future(); + + // We wait for new systems to be discovered, once we find one that has an + // autopilot, we decide to use it. + mavsdk.subscribe_on_new_system([&mavsdk, &prom]() { + auto system = mavsdk.systems().back(); + + // Unsubscribe again as we only want to find one system. + mavsdk.subscribe_on_new_system(nullptr); + prom.set_value(system); + }); + + // We usually receive heartbeats at 1Hz, therefore we should find a + // system after around 3 seconds max, surely. + if (fut.wait_for(seconds(3)) == std::future_status::timeout) { + std::cerr << "No autopilot found.\n"; + return {}; + } + + // Get discovered system now. + return fut.get(); +} + +int main(int argc, char** argv) +{ + if (argc > 3) { + usage(argv[0]); + return 1; + } + + /* parse arguments */ + bool remove_log_files = false; + + for (int i = 2; i < argc; ++i) { + if (argv[i] == "--rm") { + remove_log_files = true; + } + } + + Mavsdk mavsdk; + 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 = get_system(mavsdk); + if (!system) { + return 1; + } + + // Instantiate plugins. + + auto log_files = LogFiles{system}; + + auto get_entries_result = log_files.get_entries(); + if (get_entries_result.first == LogFiles::Result::Success) { + bool download_failure = false; + for (auto entry : get_entries_result.second) { + std::cerr << "Got log file with ID " << entry.id << " and date " << entry.date + << std::endl; + auto result = + log_files.download_log_file(entry, std::string("log-") + entry.date + ".ulg"); + if (result.first != LogFiles::Result::Success) { + download_failure = true; + std::cerr << "LogFiles::download_log_file failed: " << result.first << std::endl; + } + } + if (!download_failure && remove_log_files) { + /* + * If you want to be sure the log has been deleted, call get_entries again + * that there are no log files present anymore + * + * TODO: provide a more reliable solution + */ + log_files.erase_all_log_files(); + } + } else { + std::cerr << "LogFiles::get_entries failed: " << get_entries_result.first << std::endl; + return 1; + } + + return 0; +} diff --git a/proto b/proto index c02e228be9..e74179a049 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit c02e228be9261e2ff56e7ced268c6739b4d21a87 +Subproject commit e74179a049fd74c570ece9fc19b95388cdc4068d diff --git a/src/mavsdk/plugins/log_files/include/plugins/log_files/log_files.h b/src/mavsdk/plugins/log_files/include/plugins/log_files/log_files.h index 2ee945972c..30970896cd 100644 --- a/src/mavsdk/plugins/log_files/include/plugins/log_files/log_files.h +++ b/src/mavsdk/plugins/log_files/include/plugins/log_files/log_files.h @@ -160,6 +160,25 @@ class LogFiles : public PluginBase { */ void download_log_file_async(Entry entry, std::string path, DownloadLogFileCallback callback); + /** + * @brief Download log file synchronously. + * + * This function is blocking. + * + * @return Result of request. + */ + std::pair + download_log_file(Entry entry, std::string path) const; + + /** + * @brief Erase all log files. + * + * This function is blocking. + * + * @return Result of request. + */ + Result erase_all_log_files() const; + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/log_files/log_files.cpp b/src/mavsdk/plugins/log_files/log_files.cpp index 4575adc5cb..2bb9b06488 100644 --- a/src/mavsdk/plugins/log_files/log_files.cpp +++ b/src/mavsdk/plugins/log_files/log_files.cpp @@ -37,6 +37,17 @@ void LogFiles::download_log_file_async( _impl->download_log_file_async(entry, path, callback); } +std::pair +LogFiles::download_log_file(Entry entry, std::string path) const +{ + return _impl->download_log_file(entry, path); +} + +LogFiles::Result LogFiles::erase_all_log_files() const +{ + return _impl->erase_all_log_files(); +} + bool operator==(const LogFiles::ProgressData& lhs, const LogFiles::ProgressData& rhs) { return ((std::isnan(rhs.progress) && std::isnan(lhs.progress)) || rhs.progress == lhs.progress); diff --git a/src/mavsdk/plugins/log_files/log_files_impl.cpp b/src/mavsdk/plugins/log_files/log_files_impl.cpp index cbfa66e5e9..e349927ad2 100644 --- a/src/mavsdk/plugins/log_files/log_files_impl.cpp +++ b/src/mavsdk/plugins/log_files/log_files_impl.cpp @@ -1,6 +1,7 @@ #include "log_files_impl.h" #include "mavsdk_impl.h" #include "filesystem_include.h" +#include "unused.h" #include #include @@ -202,6 +203,23 @@ void LogFilesImpl::list_timeout() } } +std::pair +LogFilesImpl::download_log_file(LogFiles::Entry entry, const std::string& file_path) +{ + auto prom = + std::make_shared>>(); + auto future_result = prom->get_future(); + + download_log_file_async( + entry, file_path, [prom](LogFiles::Result result, LogFiles::ProgressData progress) { + UNUSED(progress); + if (result != LogFiles::Result::Next) { + prom->set_value(std::make_pair(result, progress)); + } + }); + return future_result.get(); +} + void LogFilesImpl::download_log_file_async( LogFiles::Entry entry, const std::string& file_path, LogFiles::DownloadLogFileCallback callback) { @@ -295,6 +313,21 @@ void LogFilesImpl::download_log_file_async( } } +LogFiles::Result LogFilesImpl::erase_all_log_files() +{ + mavlink_message_t msg; + mavlink_msg_log_erase_pack( + _parent->get_own_system_id(), + _parent->get_own_component_id(), + &msg, + _parent->get_system_id(), + MAV_COMP_ID_AUTOPILOT1); + _parent->send_message(msg); + + // TODO: find a good way to know about the success or failure of the operation + return LogFiles::Result::Success; +} + std::size_t LogFilesImpl::determine_part_end() { // Assumes to have the lock for _data.mutex. diff --git a/src/mavsdk/plugins/log_files/log_files_impl.h b/src/mavsdk/plugins/log_files/log_files_impl.h index 2b587189d8..46c28ebb9b 100644 --- a/src/mavsdk/plugins/log_files/log_files_impl.h +++ b/src/mavsdk/plugins/log_files/log_files_impl.h @@ -23,11 +23,15 @@ class LogFilesImpl : public PluginImplBase { std::pair> get_entries(); void get_entries_async(LogFiles::GetEntriesCallback callback); + std::pair + download_log_file(LogFiles::Entry entry, const std::string& file_path); void download_log_file_async( LogFiles::Entry entry, const std::string& file_path, LogFiles::DownloadLogFileCallback callback); + LogFiles::Result erase_all_log_files(); + private: void request_end(); diff --git a/src/mavsdk_server/src/generated/log_files/log_files.grpc.pb.cc b/src/mavsdk_server/src/generated/log_files/log_files.grpc.pb.cc index a7726d3eff..2446b02f35 100644 --- a/src/mavsdk_server/src/generated/log_files/log_files.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/log_files/log_files.grpc.pb.cc @@ -26,6 +26,8 @@ namespace log_files { static const char* LogFilesService_method_names[] = { "/mavsdk.rpc.log_files.LogFilesService/GetEntries", "/mavsdk.rpc.log_files.LogFilesService/SubscribeDownloadLogFile", + "/mavsdk.rpc.log_files.LogFilesService/DownloadLogFile", + "/mavsdk.rpc.log_files.LogFilesService/EraseAllLogFiles", }; std::unique_ptr< LogFilesService::Stub> LogFilesService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -37,6 +39,8 @@ std::unique_ptr< LogFilesService::Stub> LogFilesService::NewStub(const std::shar LogFilesService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) : channel_(channel), rpcmethod_GetEntries_(LogFilesService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeDownloadLogFile_(LogFilesService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_DownloadLogFile_(LogFilesService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_EraseAllLogFiles_(LogFilesService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status LogFilesService::Stub::GetEntries(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::GetEntriesRequest& request, ::mavsdk::rpc::log_files::GetEntriesResponse* response) { @@ -78,6 +82,52 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* L return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::log_files::DownloadLogFileResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeDownloadLogFile_, context, request, false, nullptr); } +::grpc::Status LogFilesService::Stub::DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::mavsdk::rpc::log_files::DownloadLogFileResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_DownloadLogFile_, context, request, response); +} + +void LogFilesService::Stub::async::DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::mavsdk::rpc::log_files::DownloadLogFileResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_DownloadLogFile_, context, request, response, std::move(f)); +} + +void LogFilesService::Stub::async::DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_DownloadLogFile_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* LogFilesService::Stub::PrepareAsyncDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::log_files::DownloadLogFileResponse, ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_DownloadLogFile_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* LogFilesService::Stub::AsyncDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncDownloadLogFileRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status LogFilesService::Stub::EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_EraseAllLogFiles_, context, request, response); +} + +void LogFilesService::Stub::async::EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_EraseAllLogFiles_, context, request, response, std::move(f)); +} + +void LogFilesService::Stub::async::EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_EraseAllLogFiles_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* LogFilesService::Stub::PrepareAsyncEraseAllLogFilesRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse, ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_EraseAllLogFiles_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* LogFilesService::Stub::AsyncEraseAllLogFilesRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncEraseAllLogFilesRaw(context, request, cq); + result->StartCall(); + return result; +} + LogFilesService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( LogFilesService_method_names[0], @@ -99,6 +149,26 @@ LogFilesService::Service::Service() { ::grpc::ServerWriter<::mavsdk::rpc::log_files::DownloadLogFileResponse>* writer) { return service->SubscribeDownloadLogFile(ctx, req, writer); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + LogFilesService_method_names[2], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< LogFilesService::Service, ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::mavsdk::rpc::log_files::DownloadLogFileResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](LogFilesService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::log_files::DownloadLogFileRequest* req, + ::mavsdk::rpc::log_files::DownloadLogFileResponse* resp) { + return service->DownloadLogFile(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + LogFilesService_method_names[3], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< LogFilesService::Service, ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](LogFilesService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* req, + ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* resp) { + return service->EraseAllLogFiles(ctx, req, resp); + }, this))); } LogFilesService::Service::~Service() { @@ -118,6 +188,20 @@ ::grpc::Status LogFilesService::Service::SubscribeDownloadLogFile(::grpc::Server return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status LogFilesService::Service::DownloadLogFile(::grpc::ServerContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status LogFilesService::Service::EraseAllLogFiles(::grpc::ServerContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/log_files/log_files.grpc.pb.h b/src/mavsdk_server/src/generated/log_files/log_files.grpc.pb.h index e95e9b8c2a..d4221fbb30 100644 --- a/src/mavsdk_server/src/generated/log_files/log_files.grpc.pb.h +++ b/src/mavsdk_server/src/generated/log_files/log_files.grpc.pb.h @@ -57,6 +57,22 @@ class LogFilesService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>> PrepareAsyncSubscribeDownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>>(PrepareAsyncSubscribeDownloadLogFileRaw(context, request, cq)); } + // Download log file synchronously. + virtual ::grpc::Status DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>> AsyncDownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>>(AsyncDownloadLogFileRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>> PrepareAsyncDownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>>(PrepareAsyncDownloadLogFileRaw(context, request, cq)); + } + // Erase all log files. + virtual ::grpc::Status EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>> AsyncEraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>>(AsyncEraseAllLogFilesRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>> PrepareAsyncEraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>>(PrepareAsyncEraseAllLogFilesRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -65,6 +81,12 @@ class LogFilesService final { virtual void GetEntries(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::GetEntriesRequest* request, ::mavsdk::rpc::log_files::GetEntriesResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // Download log file. virtual void SubscribeDownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* reactor) = 0; + // Download log file synchronously. + virtual void DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response, std::function) = 0; + virtual void DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Erase all log files. + virtual void EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response, std::function) = 0; + virtual void EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -75,6 +97,10 @@ class LogFilesService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* SubscribeDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* AsyncSubscribeDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* PrepareAsyncSubscribeDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* AsyncDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* PrepareAsyncDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* AsyncEraseAllLogFilesRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* PrepareAsyncEraseAllLogFilesRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -95,12 +121,30 @@ class LogFilesService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>> PrepareAsyncSubscribeDownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>>(PrepareAsyncSubscribeDownloadLogFileRaw(context, request, cq)); } + ::grpc::Status DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>> AsyncDownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>>(AsyncDownloadLogFileRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>> PrepareAsyncDownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>>(PrepareAsyncDownloadLogFileRaw(context, request, cq)); + } + ::grpc::Status EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>> AsyncEraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>>(AsyncEraseAllLogFilesRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>> PrepareAsyncEraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>>(PrepareAsyncEraseAllLogFilesRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: void GetEntries(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::GetEntriesRequest* request, ::mavsdk::rpc::log_files::GetEntriesResponse* response, std::function) override; void GetEntries(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::GetEntriesRequest* request, ::mavsdk::rpc::log_files::GetEntriesResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeDownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* reactor) override; + void DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response, std::function) override; + void DownloadLogFile(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response, std::function) override; + void EraseAllLogFiles(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -117,8 +161,14 @@ class LogFilesService final { ::grpc::ClientReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* SubscribeDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* AsyncSubscribeDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* PrepareAsyncSubscribeDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* AsyncDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* PrepareAsyncDownloadLogFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* AsyncEraseAllLogFilesRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* PrepareAsyncEraseAllLogFilesRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_GetEntries_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeDownloadLogFile_; + const ::grpc::internal::RpcMethod rpcmethod_DownloadLogFile_; + const ::grpc::internal::RpcMethod rpcmethod_EraseAllLogFiles_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -130,6 +180,10 @@ class LogFilesService final { virtual ::grpc::Status GetEntries(::grpc::ServerContext* context, const ::mavsdk::rpc::log_files::GetEntriesRequest* request, ::mavsdk::rpc::log_files::GetEntriesResponse* response); // Download log file. virtual ::grpc::Status SubscribeDownloadLogFile(::grpc::ServerContext* context, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* writer); + // Download log file synchronously. + virtual ::grpc::Status DownloadLogFile(::grpc::ServerContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response); + // Erase all log files. + virtual ::grpc::Status EraseAllLogFiles(::grpc::ServerContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response); }; template class WithAsyncMethod_GetEntries : public BaseClass { @@ -171,7 +225,47 @@ class LogFilesService final { ::grpc::Service::RequestAsyncServerStreaming(1, context, request, writer, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_GetEntries > AsyncService; + template + class WithAsyncMethod_DownloadLogFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_DownloadLogFile() { + ::grpc::Service::MarkMethodAsync(2); + } + ~WithAsyncMethod_DownloadLogFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status DownloadLogFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* /*request*/, ::mavsdk::rpc::log_files::DownloadLogFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestDownloadLogFile(::grpc::ServerContext* context, ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_EraseAllLogFiles : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_EraseAllLogFiles() { + ::grpc::Service::MarkMethodAsync(3); + } + ~WithAsyncMethod_EraseAllLogFiles() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status EraseAllLogFiles(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* /*request*/, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestEraseAllLogFiles(::grpc::ServerContext* context, ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_GetEntries > > > AsyncService; template class WithCallbackMethod_GetEntries : public BaseClass { private: @@ -221,7 +315,61 @@ class LogFilesService final { virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::log_files::DownloadLogFileResponse>* SubscribeDownloadLogFile( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest* /*request*/) { return nullptr; } }; - typedef WithCallbackMethod_GetEntries > CallbackService; + template + class WithCallbackMethod_DownloadLogFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_DownloadLogFile() { + ::grpc::Service::MarkMethodCallback(2, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::mavsdk::rpc::log_files::DownloadLogFileResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* request, ::mavsdk::rpc::log_files::DownloadLogFileResponse* response) { return this->DownloadLogFile(context, request, response); }));} + void SetMessageAllocatorFor_DownloadLogFile( + ::grpc::MessageAllocator< ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::mavsdk::rpc::log_files::DownloadLogFileResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::mavsdk::rpc::log_files::DownloadLogFileResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_DownloadLogFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status DownloadLogFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* /*request*/, ::mavsdk::rpc::log_files::DownloadLogFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* DownloadLogFile( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* /*request*/, ::mavsdk::rpc::log_files::DownloadLogFileResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_EraseAllLogFiles : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_EraseAllLogFiles() { + ::grpc::Service::MarkMethodCallback(3, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* request, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* response) { return this->EraseAllLogFiles(context, request, response); }));} + void SetMessageAllocatorFor_EraseAllLogFiles( + ::grpc::MessageAllocator< ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_EraseAllLogFiles() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status EraseAllLogFiles(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* /*request*/, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* EraseAllLogFiles( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* /*request*/, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_GetEntries > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_GetEntries : public BaseClass { @@ -258,6 +406,40 @@ class LogFilesService final { } }; template + class WithGenericMethod_DownloadLogFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_DownloadLogFile() { + ::grpc::Service::MarkMethodGeneric(2); + } + ~WithGenericMethod_DownloadLogFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status DownloadLogFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* /*request*/, ::mavsdk::rpc::log_files::DownloadLogFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_EraseAllLogFiles : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_EraseAllLogFiles() { + ::grpc::Service::MarkMethodGeneric(3); + } + ~WithGenericMethod_EraseAllLogFiles() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status EraseAllLogFiles(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* /*request*/, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_GetEntries : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -298,6 +480,46 @@ class LogFilesService final { } }; template + class WithRawMethod_DownloadLogFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_DownloadLogFile() { + ::grpc::Service::MarkMethodRaw(2); + } + ~WithRawMethod_DownloadLogFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status DownloadLogFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* /*request*/, ::mavsdk::rpc::log_files::DownloadLogFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestDownloadLogFile(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_EraseAllLogFiles : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_EraseAllLogFiles() { + ::grpc::Service::MarkMethodRaw(3); + } + ~WithRawMethod_EraseAllLogFiles() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status EraseAllLogFiles(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* /*request*/, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestEraseAllLogFiles(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_GetEntries : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -342,6 +564,50 @@ class LogFilesService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_DownloadLogFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_DownloadLogFile() { + ::grpc::Service::MarkMethodRawCallback(2, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->DownloadLogFile(context, request, response); })); + } + ~WithRawCallbackMethod_DownloadLogFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status DownloadLogFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* /*request*/, ::mavsdk::rpc::log_files::DownloadLogFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* DownloadLogFile( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_EraseAllLogFiles : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_EraseAllLogFiles() { + ::grpc::Service::MarkMethodRawCallback(3, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->EraseAllLogFiles(context, request, response); })); + } + ~WithRawCallbackMethod_EraseAllLogFiles() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status EraseAllLogFiles(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* /*request*/, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* EraseAllLogFiles( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_GetEntries : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -368,7 +634,61 @@ class LogFilesService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedGetEntries(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::log_files::GetEntriesRequest,::mavsdk::rpc::log_files::GetEntriesResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_GetEntries StreamedUnaryService; + template + class WithStreamedUnaryMethod_DownloadLogFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_DownloadLogFile() { + ::grpc::Service::MarkMethodStreamed(2, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::mavsdk::rpc::log_files::DownloadLogFileResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::log_files::DownloadLogFileRequest, ::mavsdk::rpc::log_files::DownloadLogFileResponse>* streamer) { + return this->StreamedDownloadLogFile(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_DownloadLogFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status DownloadLogFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::DownloadLogFileRequest* /*request*/, ::mavsdk::rpc::log_files::DownloadLogFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedDownloadLogFile(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::log_files::DownloadLogFileRequest,::mavsdk::rpc::log_files::DownloadLogFileResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_EraseAllLogFiles : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_EraseAllLogFiles() { + ::grpc::Service::MarkMethodStreamed(3, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::log_files::EraseAllLogFilesRequest, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* streamer) { + return this->StreamedEraseAllLogFiles(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_EraseAllLogFiles() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status EraseAllLogFiles(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* /*request*/, ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedEraseAllLogFiles(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::log_files::EraseAllLogFilesRequest,::mavsdk::rpc::log_files::EraseAllLogFilesResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_GetEntries > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeDownloadLogFile : public BaseClass { private: @@ -397,7 +717,7 @@ class LogFilesService final { virtual ::grpc::Status StreamedSubscribeDownloadLogFile(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest,::mavsdk::rpc::log_files::DownloadLogFileResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeDownloadLogFile SplitStreamedService; - typedef WithStreamedUnaryMethod_GetEntries > StreamedService; + typedef WithStreamedUnaryMethod_GetEntries > > > StreamedService; }; } // namespace log_files diff --git a/src/mavsdk_server/src/generated/log_files/log_files.pb.cc b/src/mavsdk_server/src/generated/log_files/log_files.pb.cc index 50ce88a8ec..2726b51b42 100644 --- a/src/mavsdk_server/src/generated/log_files/log_files.pb.cc +++ b/src/mavsdk_server/src/generated/log_files/log_files.pb.cc @@ -69,6 +69,42 @@ struct DownloadLogFileResponseDefaultTypeInternal { }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT DownloadLogFileResponseDefaultTypeInternal _DownloadLogFileResponse_default_instance_; +constexpr DownloadLogFileRequest::DownloadLogFileRequest( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : path_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , entry_(nullptr){} +struct DownloadLogFileRequestDefaultTypeInternal { + constexpr DownloadLogFileRequestDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~DownloadLogFileRequestDefaultTypeInternal() {} + union { + DownloadLogFileRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT DownloadLogFileRequestDefaultTypeInternal _DownloadLogFileRequest_default_instance_; +constexpr EraseAllLogFilesRequest::EraseAllLogFilesRequest( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized){} +struct EraseAllLogFilesRequestDefaultTypeInternal { + constexpr EraseAllLogFilesRequestDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~EraseAllLogFilesRequestDefaultTypeInternal() {} + union { + EraseAllLogFilesRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT EraseAllLogFilesRequestDefaultTypeInternal _EraseAllLogFilesRequest_default_instance_; +constexpr EraseAllLogFilesResponse::EraseAllLogFilesResponse( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : log_files_result_(nullptr){} +struct EraseAllLogFilesResponseDefaultTypeInternal { + constexpr EraseAllLogFilesResponseDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~EraseAllLogFilesResponseDefaultTypeInternal() {} + union { + EraseAllLogFilesResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT EraseAllLogFilesResponseDefaultTypeInternal _EraseAllLogFilesResponse_default_instance_; constexpr ProgressData::ProgressData( ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) : progress_(0){} @@ -112,7 +148,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT LogFilesResultDefaultTypeIntern } // namespace log_files } // namespace rpc } // namespace mavsdk -static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[7]; +static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[10]; static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_log_5ffiles_2flog_5ffiles_2eproto[1]; static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_log_5ffiles_2flog_5ffiles_2eproto = nullptr; @@ -144,6 +180,24 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_log_5ffiles_2flog_5ffiles_2epr PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::DownloadLogFileResponse, log_files_result_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::DownloadLogFileResponse, progress_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::DownloadLogFileRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::DownloadLogFileRequest, entry_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::DownloadLogFileRequest, path_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::EraseAllLogFilesRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::EraseAllLogFilesResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::EraseAllLogFilesResponse, log_files_result_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::log_files::ProgressData, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -170,9 +224,12 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB { 5, -1, sizeof(::mavsdk::rpc::log_files::GetEntriesResponse)}, { 12, -1, sizeof(::mavsdk::rpc::log_files::SubscribeDownloadLogFileRequest)}, { 19, -1, sizeof(::mavsdk::rpc::log_files::DownloadLogFileResponse)}, - { 26, -1, sizeof(::mavsdk::rpc::log_files::ProgressData)}, - { 32, -1, sizeof(::mavsdk::rpc::log_files::Entry)}, - { 40, -1, sizeof(::mavsdk::rpc::log_files::LogFilesResult)}, + { 26, -1, sizeof(::mavsdk::rpc::log_files::DownloadLogFileRequest)}, + { 33, -1, sizeof(::mavsdk::rpc::log_files::EraseAllLogFilesRequest)}, + { 38, -1, sizeof(::mavsdk::rpc::log_files::EraseAllLogFilesResponse)}, + { 44, -1, sizeof(::mavsdk::rpc::log_files::ProgressData)}, + { 50, -1, sizeof(::mavsdk::rpc::log_files::Entry)}, + { 58, -1, sizeof(::mavsdk::rpc::log_files::LogFilesResult)}, }; static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = { @@ -180,6 +237,9 @@ static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = reinterpret_cast(&::mavsdk::rpc::log_files::_GetEntriesResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::log_files::_SubscribeDownloadLogFileRequest_default_instance_), reinterpret_cast(&::mavsdk::rpc::log_files::_DownloadLogFileResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::log_files::_DownloadLogFileRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::log_files::_EraseAllLogFilesRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::log_files::_EraseAllLogFilesResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::log_files::_ProgressData_default_instance_), reinterpret_cast(&::mavsdk::rpc::log_files::_Entry_default_instance_), reinterpret_cast(&::mavsdk::rpc::log_files::_LogFilesResult_default_instance_), @@ -197,33 +257,44 @@ const char descriptor_table_protodef_log_5ffiles_2flog_5ffiles_2eproto[] PROTOBU "\001\n\027DownloadLogFileResponse\022>\n\020log_files_" "result\030\001 \001(\0132$.mavsdk.rpc.log_files.LogF" "ilesResult\0224\n\010progress\030\002 \001(\0132\".mavsdk.rp" - "c.log_files.ProgressData\")\n\014ProgressData" - "\022\031\n\010progress\030\001 \001(\002B\007\202\265\030\003NaN\"5\n\005Entry\022\n\n\002" - "id\030\001 \001(\r\022\014\n\004date\030\002 \001(\t\022\022\n\nsize_bytes\030\003 \001" - "(\r\"\241\002\n\016LogFilesResult\022;\n\006result\030\001 \001(\0162+." - "mavsdk.rpc.log_files.LogFilesResult.Resu" - "lt\022\022\n\nresult_str\030\002 \001(\t\"\275\001\n\006Result\022\022\n\016RES" - "ULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\017\n\013RES" - "ULT_NEXT\020\002\022\026\n\022RESULT_NO_LOGFILES\020\003\022\022\n\016RE" - "SULT_TIMEOUT\020\004\022\033\n\027RESULT_INVALID_ARGUMEN" - "T\020\005\022\033\n\027RESULT_FILE_OPEN_FAILED\020\006\022\024\n\020RESU" - "LT_NO_SYSTEM\020\0072\203\002\n\017LogFilesService\022a\n\nGe" - "tEntries\022\'.mavsdk.rpc.log_files.GetEntri" - "esRequest\032(.mavsdk.rpc.log_files.GetEntr" - "iesResponse\"\000\022\214\001\n\030SubscribeDownloadLogFi" - "le\0225.mavsdk.rpc.log_files.SubscribeDownl" - "oadLogFileRequest\032-.mavsdk.rpc.log_files" - ".DownloadLogFileResponse\"\010\200\265\030\000\210\265\030\0010\001B$\n\023" - "io.mavsdk.log_filesB\rLogFilesProtob\006prot" - "o3" + "c.log_files.ProgressData\"R\n\026DownloadLogF" + "ileRequest\022*\n\005entry\030\001 \001(\0132\033.mavsdk.rpc.l" + "og_files.Entry\022\014\n\004path\030\002 \001(\t\"\031\n\027EraseAll" + "LogFilesRequest\"Z\n\030EraseAllLogFilesRespo" + "nse\022>\n\020log_files_result\030\001 \001(\0132$.mavsdk.r" + "pc.log_files.LogFilesResult\")\n\014ProgressD" + "ata\022\031\n\010progress\030\001 \001(\002B\007\202\265\030\003NaN\"5\n\005Entry\022" + "\n\n\002id\030\001 \001(\r\022\014\n\004date\030\002 \001(\t\022\022\n\nsize_bytes\030" + "\003 \001(\r\"\241\002\n\016LogFilesResult\022;\n\006result\030\001 \001(\016" + "2+.mavsdk.rpc.log_files.LogFilesResult.R" + "esult\022\022\n\nresult_str\030\002 \001(\t\"\275\001\n\006Result\022\022\n\016" + "RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\017\n\013" + "RESULT_NEXT\020\002\022\026\n\022RESULT_NO_LOGFILES\020\003\022\022\n" + "\016RESULT_TIMEOUT\020\004\022\033\n\027RESULT_INVALID_ARGU" + "MENT\020\005\022\033\n\027RESULT_FILE_OPEN_FAILED\020\006\022\024\n\020R" + "ESULT_NO_SYSTEM\020\0072\362\003\n\017LogFilesService\022a\n" + "\nGetEntries\022\'.mavsdk.rpc.log_files.GetEn" + "triesRequest\032(.mavsdk.rpc.log_files.GetE" + "ntriesResponse\"\000\022\214\001\n\030SubscribeDownloadLo" + "gFile\0225.mavsdk.rpc.log_files.SubscribeDo" + "wnloadLogFileRequest\032-.mavsdk.rpc.log_fi" + "les.DownloadLogFileResponse\"\010\200\265\030\000\210\265\030\0010\001\022" + "t\n\017DownloadLogFile\022,.mavsdk.rpc.log_file" + "s.DownloadLogFileRequest\032-.mavsdk.rpc.lo" + "g_files.DownloadLogFileResponse\"\004\200\265\030\001\022w\n" + "\020EraseAllLogFiles\022-.mavsdk.rpc.log_files" + ".EraseAllLogFilesRequest\032..mavsdk.rpc.lo" + "g_files.EraseAllLogFilesResponse\"\004\200\265\030\001B$" + "\n\023io.mavsdk.log_filesB\rLogFilesProtob\006pr" + "oto3" ; static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, }; static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once; const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_log_5ffiles_2flog_5ffiles_2eproto = { - false, false, 1162, descriptor_table_protodef_log_5ffiles_2flog_5ffiles_2eproto, "log_files/log_files.proto", - &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once, descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_deps, 1, 7, + false, false, 1604, descriptor_table_protodef_log_5ffiles_2flog_5ffiles_2eproto, "log_files/log_files.proto", + &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once, descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_deps, 1, 10, schemas, file_default_instances, TableStruct_log_5ffiles_2flog_5ffiles_2eproto::offsets, file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto, file_level_enum_descriptors_log_5ffiles_2flog_5ffiles_2eproto, file_level_service_descriptors_log_5ffiles_2flog_5ffiles_2eproto, }; @@ -1147,72 +1218,102 @@ ::PROTOBUF_NAMESPACE_ID::Metadata DownloadLogFileResponse::GetMetadata() const { // =================================================================== -class ProgressData::_Internal { +class DownloadLogFileRequest::_Internal { public: + static const ::mavsdk::rpc::log_files::Entry& entry(const DownloadLogFileRequest* msg); }; -ProgressData::ProgressData(::PROTOBUF_NAMESPACE_ID::Arena* arena, +const ::mavsdk::rpc::log_files::Entry& +DownloadLogFileRequest::_Internal::entry(const DownloadLogFileRequest* msg) { + return *msg->entry_; +} +DownloadLogFileRequest::DownloadLogFileRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned) : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { SharedCtor(); if (!is_message_owned) { RegisterArenaDtor(arena); } - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_files.ProgressData) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_files.DownloadLogFileRequest) } -ProgressData::ProgressData(const ProgressData& from) +DownloadLogFileRequest::DownloadLogFileRequest(const DownloadLogFileRequest& from) : ::PROTOBUF_NAMESPACE_ID::Message() { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - progress_ = from.progress_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_files.ProgressData) + path_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_path().empty()) { + path_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_path(), + GetArenaForAllocation()); + } + if (from._internal_has_entry()) { + entry_ = new ::mavsdk::rpc::log_files::Entry(*from.entry_); + } else { + entry_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_files.DownloadLogFileRequest) } -inline void ProgressData::SharedCtor() { -progress_ = 0; +inline void DownloadLogFileRequest::SharedCtor() { +path_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +entry_ = nullptr; } -ProgressData::~ProgressData() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.log_files.ProgressData) +DownloadLogFileRequest::~DownloadLogFileRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_files.DownloadLogFileRequest) if (GetArenaForAllocation() != nullptr) return; SharedDtor(); _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -inline void ProgressData::SharedDtor() { +inline void DownloadLogFileRequest::SharedDtor() { GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + path_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete entry_; } -void ProgressData::ArenaDtor(void* object) { - ProgressData* _this = reinterpret_cast< ProgressData* >(object); +void DownloadLogFileRequest::ArenaDtor(void* object) { + DownloadLogFileRequest* _this = reinterpret_cast< DownloadLogFileRequest* >(object); (void)_this; } -void ProgressData::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +void DownloadLogFileRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { } -void ProgressData::SetCachedSize(int size) const { +void DownloadLogFileRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -void ProgressData::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_files.ProgressData) +void DownloadLogFileRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_files.DownloadLogFileRequest) ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - progress_ = 0; + path_.ClearToEmpty(); + if (GetArenaForAllocation() == nullptr && entry_ != nullptr) { + delete entry_; + } + entry_ = nullptr; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* ProgressData::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +const char* DownloadLogFileRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::PROTOBUF_NAMESPACE_ID::uint32 tag; ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); switch (tag >> 3) { - // float progress = 1 [(.mavsdk.options.default_value) = "NaN"]; + // .mavsdk.rpc.log_files.Entry entry = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 13)) { - progress_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_entry(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // string path = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18)) { + auto str = _internal_mutable_path(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.log_files.DownloadLogFileRequest.path")); + CHK_(ptr); } else goto handle_unusual; continue; default: { @@ -1238,37 +1339,58 @@ const char* ProgressData::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_I #undef CHK_ } -::PROTOBUF_NAMESPACE_ID::uint8* ProgressData::_InternalSerialize( +::PROTOBUF_NAMESPACE_ID::uint8* DownloadLogFileRequest::_InternalSerialize( ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_files.ProgressData) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_files.DownloadLogFileRequest) ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float progress = 1 [(.mavsdk.options.default_value) = "NaN"]; - if (!(this->_internal_progress() <= 0 && this->_internal_progress() >= 0)) { + // .mavsdk.rpc.log_files.Entry entry = 1; + if (this->_internal_has_entry()) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_progress(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::entry(this), target, stream); + } + + // string path = 2; + if (!this->_internal_path().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_path().data(), static_cast(this->_internal_path().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.log_files.DownloadLogFileRequest.path"); + target = stream->WriteStringMaybeAliased( + 2, this->_internal_path(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.log_files.ProgressData) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.log_files.DownloadLogFileRequest) return target; } -size_t ProgressData::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_files.ProgressData) +size_t DownloadLogFileRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_files.DownloadLogFileRequest) size_t total_size = 0; ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float progress = 1 [(.mavsdk.options.default_value) = "NaN"]; - if (!(this->_internal_progress() <= 0 && this->_internal_progress() >= 0)) { - total_size += 1 + 4; + // string path = 2; + if (!this->_internal_path().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_path()); + } + + // .mavsdk.rpc.log_files.Entry entry = 1; + if (this->_internal_has_entry()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *entry_); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -1280,49 +1402,57 @@ size_t ProgressData::ByteSizeLong() const { return total_size; } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ProgressData::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData DownloadLogFileRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, - ProgressData::MergeImpl + DownloadLogFileRequest::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ProgressData::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*DownloadLogFileRequest::GetClassData() const { return &_class_data_; } -void ProgressData::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, +void DownloadLogFileRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from) { - static_cast(to)->MergeFrom( - static_cast(from)); + static_cast(to)->MergeFrom( + static_cast(from)); } -void ProgressData::MergeFrom(const ProgressData& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.log_files.ProgressData) +void DownloadLogFileRequest::MergeFrom(const DownloadLogFileRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.log_files.DownloadLogFileRequest) GOOGLE_DCHECK_NE(&from, this); ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (!(from._internal_progress() <= 0 && from._internal_progress() >= 0)) { - _internal_set_progress(from._internal_progress()); + if (!from._internal_path().empty()) { + _internal_set_path(from._internal_path()); + } + if (from._internal_has_entry()) { + _internal_mutable_entry()->::mavsdk::rpc::log_files::Entry::MergeFrom(from._internal_entry()); } _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void ProgressData::CopyFrom(const ProgressData& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_files.ProgressData) +void DownloadLogFileRequest::CopyFrom(const DownloadLogFileRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_files.DownloadLogFileRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool ProgressData::IsInitialized() const { +bool DownloadLogFileRequest::IsInitialized() const { return true; } -void ProgressData::InternalSwap(ProgressData* other) { +void DownloadLogFileRequest::InternalSwap(DownloadLogFileRequest* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(progress_, other->progress_); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &path_, GetArenaForAllocation(), + &other->path_, other->GetArenaForAllocation() + ); + swap(entry_, other->entry_); } -::PROTOBUF_NAMESPACE_ID::Metadata ProgressData::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata DownloadLogFileRequest::GetMetadata() const { return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_getter, &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once, file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[4]); @@ -1330,107 +1460,63 @@ ::PROTOBUF_NAMESPACE_ID::Metadata ProgressData::GetMetadata() const { // =================================================================== -class Entry::_Internal { +class EraseAllLogFilesRequest::_Internal { public: }; -Entry::Entry(::PROTOBUF_NAMESPACE_ID::Arena* arena, +EraseAllLogFilesRequest::EraseAllLogFilesRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned) : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { SharedCtor(); if (!is_message_owned) { RegisterArenaDtor(arena); } - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_files.Entry) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_files.EraseAllLogFilesRequest) } -Entry::Entry(const Entry& from) +EraseAllLogFilesRequest::EraseAllLogFilesRequest(const EraseAllLogFilesRequest& from) : ::PROTOBUF_NAMESPACE_ID::Message() { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - date_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); - if (!from._internal_date().empty()) { - date_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_date(), - GetArenaForAllocation()); - } - ::memcpy(&id_, &from.id_, - static_cast(reinterpret_cast(&size_bytes_) - - reinterpret_cast(&id_)) + sizeof(size_bytes_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_files.Entry) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_files.EraseAllLogFilesRequest) } -inline void Entry::SharedCtor() { -date_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); -::memset(reinterpret_cast(this) + static_cast( - reinterpret_cast(&id_) - reinterpret_cast(this)), - 0, static_cast(reinterpret_cast(&size_bytes_) - - reinterpret_cast(&id_)) + sizeof(size_bytes_)); +inline void EraseAllLogFilesRequest::SharedCtor() { } -Entry::~Entry() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.log_files.Entry) +EraseAllLogFilesRequest::~EraseAllLogFilesRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_files.EraseAllLogFilesRequest) if (GetArenaForAllocation() != nullptr) return; SharedDtor(); _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -inline void Entry::SharedDtor() { +inline void EraseAllLogFilesRequest::SharedDtor() { GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); - date_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); } -void Entry::ArenaDtor(void* object) { - Entry* _this = reinterpret_cast< Entry* >(object); +void EraseAllLogFilesRequest::ArenaDtor(void* object) { + EraseAllLogFilesRequest* _this = reinterpret_cast< EraseAllLogFilesRequest* >(object); (void)_this; } -void Entry::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +void EraseAllLogFilesRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { } -void Entry::SetCachedSize(int size) const { +void EraseAllLogFilesRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -void Entry::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_files.Entry) +void EraseAllLogFilesRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_files.EraseAllLogFilesRequest) ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - date_.ClearToEmpty(); - ::memset(&id_, 0, static_cast( - reinterpret_cast(&size_bytes_) - - reinterpret_cast(&id_)) + sizeof(size_bytes_)); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* Entry::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +const char* EraseAllLogFilesRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::PROTOBUF_NAMESPACE_ID::uint32 tag; ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); - switch (tag >> 3) { - // uint32 id = 1; - case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 8)) { - id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); - } else goto handle_unusual; - continue; - // string date = 2; - case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18)) { - auto str = _internal_mutable_date(); - ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); - CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.log_files.Entry.date")); - CHK_(ptr); - } else goto handle_unusual; - continue; - // uint32 size_bytes = 3; - case 3: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 24)) { - size_bytes_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); - } else goto handle_unusual; - continue; - default: { - handle_unusual: if ((tag == 0) || ((tag & 7) == 4)) { CHK_(ptr); ctx->SetLastTag(tag); @@ -1441,8 +1527,6 @@ const char* Entry::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::inte ptr, ctx); CHK_(ptr != nullptr); continue; - } - } // switch } // while success: return ptr; @@ -1452,62 +1536,644 @@ const char* Entry::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::inte #undef CHK_ } -::PROTOBUF_NAMESPACE_ID::uint8* Entry::_InternalSerialize( +::PROTOBUF_NAMESPACE_ID::uint8* EraseAllLogFilesRequest::_InternalSerialize( ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_files.Entry) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_files.EraseAllLogFilesRequest) ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; (void) cached_has_bits; - // uint32 id = 1; - if (this->_internal_id() != 0) { - target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(1, this->_internal_id(), target); - } - - // string date = 2; - if (!this->_internal_date().empty()) { - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - this->_internal_date().data(), static_cast(this->_internal_date().length()), - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, - "mavsdk.rpc.log_files.Entry.date"); - target = stream->WriteStringMaybeAliased( - 2, this->_internal_date(), target); - } - - // uint32 size_bytes = 3; - if (this->_internal_size_bytes() != 0) { - target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(3, this->_internal_size_bytes(), target); - } - if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.log_files.Entry) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.log_files.EraseAllLogFilesRequest) return target; } -size_t Entry::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_files.Entry) +size_t EraseAllLogFilesRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_files.EraseAllLogFilesRequest) size_t total_size = 0; ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // string date = 2; - if (!this->_internal_date().empty()) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_date()); + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} - // uint32 id = 1; - if (this->_internal_id() != 0) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( - this->_internal_id()); +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData EraseAllLogFilesRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + EraseAllLogFilesRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*EraseAllLogFilesRequest::GetClassData() const { return &_class_data_; } + +void EraseAllLogFilesRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void EraseAllLogFilesRequest::MergeFrom(const EraseAllLogFilesRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.log_files.EraseAllLogFilesRequest) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void EraseAllLogFilesRequest::CopyFrom(const EraseAllLogFilesRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_files.EraseAllLogFilesRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool EraseAllLogFilesRequest::IsInitialized() const { + return true; +} + +void EraseAllLogFilesRequest::InternalSwap(EraseAllLogFilesRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata EraseAllLogFilesRequest::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_getter, &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once, + file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[5]); +} + +// =================================================================== + +class EraseAllLogFilesResponse::_Internal { + public: + static const ::mavsdk::rpc::log_files::LogFilesResult& log_files_result(const EraseAllLogFilesResponse* msg); +}; + +const ::mavsdk::rpc::log_files::LogFilesResult& +EraseAllLogFilesResponse::_Internal::log_files_result(const EraseAllLogFilesResponse* msg) { + return *msg->log_files_result_; +} +EraseAllLogFilesResponse::EraseAllLogFilesResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_files.EraseAllLogFilesResponse) +} +EraseAllLogFilesResponse::EraseAllLogFilesResponse(const EraseAllLogFilesResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_log_files_result()) { + log_files_result_ = new ::mavsdk::rpc::log_files::LogFilesResult(*from.log_files_result_); + } else { + log_files_result_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_files.EraseAllLogFilesResponse) +} + +inline void EraseAllLogFilesResponse::SharedCtor() { +log_files_result_ = nullptr; +} + +EraseAllLogFilesResponse::~EraseAllLogFilesResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_files.EraseAllLogFilesResponse) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void EraseAllLogFilesResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete log_files_result_; +} + +void EraseAllLogFilesResponse::ArenaDtor(void* object) { + EraseAllLogFilesResponse* _this = reinterpret_cast< EraseAllLogFilesResponse* >(object); + (void)_this; +} +void EraseAllLogFilesResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void EraseAllLogFilesResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void EraseAllLogFilesResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_files.EraseAllLogFilesResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && log_files_result_ != nullptr) { + delete log_files_result_; + } + log_files_result_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* EraseAllLogFilesResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.log_files.LogFilesResult log_files_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_log_files_result(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* EraseAllLogFilesResponse::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_files.EraseAllLogFilesResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.log_files.LogFilesResult log_files_result = 1; + if (this->_internal_has_log_files_result()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::log_files_result(this), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.log_files.EraseAllLogFilesResponse) + return target; +} + +size_t EraseAllLogFilesResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_files.EraseAllLogFilesResponse) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.log_files.LogFilesResult log_files_result = 1; + if (this->_internal_has_log_files_result()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *log_files_result_); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData EraseAllLogFilesResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + EraseAllLogFilesResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*EraseAllLogFilesResponse::GetClassData() const { return &_class_data_; } + +void EraseAllLogFilesResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void EraseAllLogFilesResponse::MergeFrom(const EraseAllLogFilesResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.log_files.EraseAllLogFilesResponse) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_log_files_result()) { + _internal_mutable_log_files_result()->::mavsdk::rpc::log_files::LogFilesResult::MergeFrom(from._internal_log_files_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void EraseAllLogFilesResponse::CopyFrom(const EraseAllLogFilesResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_files.EraseAllLogFilesResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool EraseAllLogFilesResponse::IsInitialized() const { + return true; +} + +void EraseAllLogFilesResponse::InternalSwap(EraseAllLogFilesResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(log_files_result_, other->log_files_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata EraseAllLogFilesResponse::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_getter, &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once, + file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[6]); +} + +// =================================================================== + +class ProgressData::_Internal { + public: +}; + +ProgressData::ProgressData(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_files.ProgressData) +} +ProgressData::ProgressData(const ProgressData& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + progress_ = from.progress_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_files.ProgressData) +} + +inline void ProgressData::SharedCtor() { +progress_ = 0; +} + +ProgressData::~ProgressData() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_files.ProgressData) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void ProgressData::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); +} + +void ProgressData::ArenaDtor(void* object) { + ProgressData* _this = reinterpret_cast< ProgressData* >(object); + (void)_this; +} +void ProgressData::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void ProgressData::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void ProgressData::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_files.ProgressData) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + progress_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* ProgressData::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // float progress = 1 [(.mavsdk.options.default_value) = "NaN"]; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 13)) { + progress_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* ProgressData::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_files.ProgressData) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float progress = 1 [(.mavsdk.options.default_value) = "NaN"]; + if (!(this->_internal_progress() <= 0 && this->_internal_progress() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_progress(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.log_files.ProgressData) + return target; +} + +size_t ProgressData::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_files.ProgressData) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float progress = 1 [(.mavsdk.options.default_value) = "NaN"]; + if (!(this->_internal_progress() <= 0 && this->_internal_progress() >= 0)) { + total_size += 1 + 4; + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ProgressData::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + ProgressData::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ProgressData::GetClassData() const { return &_class_data_; } + +void ProgressData::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void ProgressData::MergeFrom(const ProgressData& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.log_files.ProgressData) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!(from._internal_progress() <= 0 && from._internal_progress() >= 0)) { + _internal_set_progress(from._internal_progress()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void ProgressData::CopyFrom(const ProgressData& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.log_files.ProgressData) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ProgressData::IsInitialized() const { + return true; +} + +void ProgressData::InternalSwap(ProgressData* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(progress_, other->progress_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata ProgressData::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_getter, &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once, + file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[7]); +} + +// =================================================================== + +class Entry::_Internal { + public: +}; + +Entry::Entry(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.log_files.Entry) +} +Entry::Entry(const Entry& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + date_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_date().empty()) { + date_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_date(), + GetArenaForAllocation()); + } + ::memcpy(&id_, &from.id_, + static_cast(reinterpret_cast(&size_bytes_) - + reinterpret_cast(&id_)) + sizeof(size_bytes_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.log_files.Entry) +} + +inline void Entry::SharedCtor() { +date_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +::memset(reinterpret_cast(this) + static_cast( + reinterpret_cast(&id_) - reinterpret_cast(this)), + 0, static_cast(reinterpret_cast(&size_bytes_) - + reinterpret_cast(&id_)) + sizeof(size_bytes_)); +} + +Entry::~Entry() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.log_files.Entry) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void Entry::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + date_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +} + +void Entry::ArenaDtor(void* object) { + Entry* _this = reinterpret_cast< Entry* >(object); + (void)_this; +} +void Entry::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void Entry::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void Entry::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.log_files.Entry) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + date_.ClearToEmpty(); + ::memset(&id_, 0, static_cast( + reinterpret_cast(&size_bytes_) - + reinterpret_cast(&id_)) + sizeof(size_bytes_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* Entry::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // uint32 id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 8)) { + id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // string date = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18)) { + auto str = _internal_mutable_date(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.log_files.Entry.date")); + CHK_(ptr); + } else goto handle_unusual; + continue; + // uint32 size_bytes = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 24)) { + size_bytes_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* Entry::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.log_files.Entry) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // uint32 id = 1; + if (this->_internal_id() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(1, this->_internal_id(), target); + } + + // string date = 2; + if (!this->_internal_date().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_date().data(), static_cast(this->_internal_date().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.log_files.Entry.date"); + target = stream->WriteStringMaybeAliased( + 2, this->_internal_date(), target); + } + + // uint32 size_bytes = 3; + if (this->_internal_size_bytes() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(3, this->_internal_size_bytes(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.log_files.Entry) + return target; +} + +size_t Entry::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.log_files.Entry) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string date = 2; + if (!this->_internal_date().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_date()); + } + + // uint32 id = 1; + if (this->_internal_id() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( + this->_internal_id()); } // uint32 size_bytes = 3; @@ -1587,7 +2253,7 @@ void Entry::InternalSwap(Entry* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Entry::GetMetadata() const { return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_getter, &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once, - file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[5]); + file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[8]); } // =================================================================== @@ -1815,7 +2481,7 @@ void LogFilesResult::InternalSwap(LogFilesResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata LogFilesResult::GetMetadata() const { return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_getter, &descriptor_table_log_5ffiles_2flog_5ffiles_2eproto_once, - file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[6]); + file_level_metadata_log_5ffiles_2flog_5ffiles_2eproto[9]); } // @@protoc_insertion_point(namespace_scope) @@ -1835,6 +2501,15 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::log_files::SubscribeDownloadLogFileR template<> PROTOBUF_NOINLINE ::mavsdk::rpc::log_files::DownloadLogFileResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::log_files::DownloadLogFileResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::log_files::DownloadLogFileResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::log_files::DownloadLogFileRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::log_files::DownloadLogFileRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::log_files::DownloadLogFileRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::log_files::EraseAllLogFilesRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::log_files::EraseAllLogFilesRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::log_files::EraseAllLogFilesResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::log_files::ProgressData* Arena::CreateMaybeMessage< ::mavsdk::rpc::log_files::ProgressData >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::log_files::ProgressData >(arena); } diff --git a/src/mavsdk_server/src/generated/log_files/log_files.pb.h b/src/mavsdk_server/src/generated/log_files/log_files.pb.h index 2eadbca2a3..f64d421f4e 100644 --- a/src/mavsdk_server/src/generated/log_files/log_files.pb.h +++ b/src/mavsdk_server/src/generated/log_files/log_files.pb.h @@ -48,7 +48,7 @@ struct TableStruct_log_5ffiles_2flog_5ffiles_2eproto { PROTOBUF_SECTION_VARIABLE(protodesc_cold); static const ::PROTOBUF_NAMESPACE_ID::internal::AuxiliaryParseTableField aux[] PROTOBUF_SECTION_VARIABLE(protodesc_cold); - static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[7] + static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[10] PROTOBUF_SECTION_VARIABLE(protodesc_cold); static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[]; static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[]; @@ -58,12 +58,21 @@ extern const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table namespace mavsdk { namespace rpc { namespace log_files { +class DownloadLogFileRequest; +struct DownloadLogFileRequestDefaultTypeInternal; +extern DownloadLogFileRequestDefaultTypeInternal _DownloadLogFileRequest_default_instance_; class DownloadLogFileResponse; struct DownloadLogFileResponseDefaultTypeInternal; extern DownloadLogFileResponseDefaultTypeInternal _DownloadLogFileResponse_default_instance_; class Entry; struct EntryDefaultTypeInternal; extern EntryDefaultTypeInternal _Entry_default_instance_; +class EraseAllLogFilesRequest; +struct EraseAllLogFilesRequestDefaultTypeInternal; +extern EraseAllLogFilesRequestDefaultTypeInternal _EraseAllLogFilesRequest_default_instance_; +class EraseAllLogFilesResponse; +struct EraseAllLogFilesResponseDefaultTypeInternal; +extern EraseAllLogFilesResponseDefaultTypeInternal _EraseAllLogFilesResponse_default_instance_; class GetEntriesRequest; struct GetEntriesRequestDefaultTypeInternal; extern GetEntriesRequestDefaultTypeInternal _GetEntriesRequest_default_instance_; @@ -83,8 +92,11 @@ extern SubscribeDownloadLogFileRequestDefaultTypeInternal _SubscribeDownloadLogF } // namespace rpc } // namespace mavsdk PROTOBUF_NAMESPACE_OPEN +template<> ::mavsdk::rpc::log_files::DownloadLogFileRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::log_files::DownloadLogFileRequest>(Arena*); template<> ::mavsdk::rpc::log_files::DownloadLogFileResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::log_files::DownloadLogFileResponse>(Arena*); template<> ::mavsdk::rpc::log_files::Entry* Arena::CreateMaybeMessage<::mavsdk::rpc::log_files::Entry>(Arena*); +template<> ::mavsdk::rpc::log_files::EraseAllLogFilesRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::log_files::EraseAllLogFilesRequest>(Arena*); +template<> ::mavsdk::rpc::log_files::EraseAllLogFilesResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::log_files::EraseAllLogFilesResponse>(Arena*); template<> ::mavsdk::rpc::log_files::GetEntriesRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::log_files::GetEntriesRequest>(Arena*); template<> ::mavsdk::rpc::log_files::GetEntriesResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::log_files::GetEntriesResponse>(Arena*); template<> ::mavsdk::rpc::log_files::LogFilesResult* Arena::CreateMaybeMessage<::mavsdk::rpc::log_files::LogFilesResult>(Arena*); @@ -754,6 +766,444 @@ class DownloadLogFileResponse final : }; // ------------------------------------------------------------------- +class DownloadLogFileRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_files.DownloadLogFileRequest) */ { + public: + inline DownloadLogFileRequest() : DownloadLogFileRequest(nullptr) {} + ~DownloadLogFileRequest() override; + explicit constexpr DownloadLogFileRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + DownloadLogFileRequest(const DownloadLogFileRequest& from); + DownloadLogFileRequest(DownloadLogFileRequest&& from) noexcept + : DownloadLogFileRequest() { + *this = ::std::move(from); + } + + inline DownloadLogFileRequest& operator=(const DownloadLogFileRequest& from) { + CopyFrom(from); + return *this; + } + inline DownloadLogFileRequest& operator=(DownloadLogFileRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const DownloadLogFileRequest& default_instance() { + return *internal_default_instance(); + } + static inline const DownloadLogFileRequest* internal_default_instance() { + return reinterpret_cast( + &_DownloadLogFileRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + friend void swap(DownloadLogFileRequest& a, DownloadLogFileRequest& b) { + a.Swap(&b); + } + inline void Swap(DownloadLogFileRequest* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(DownloadLogFileRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline DownloadLogFileRequest* New() const final { + return new DownloadLogFileRequest(); + } + + DownloadLogFileRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const DownloadLogFileRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const DownloadLogFileRequest& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(DownloadLogFileRequest* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.log_files.DownloadLogFileRequest"; + } + protected: + explicit DownloadLogFileRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kPathFieldNumber = 2, + kEntryFieldNumber = 1, + }; + // string path = 2; + void clear_path(); + const std::string& path() const; + template + void set_path(ArgT0&& arg0, ArgT... args); + std::string* mutable_path(); + PROTOBUF_MUST_USE_RESULT std::string* release_path(); + void set_allocated_path(std::string* path); + private: + const std::string& _internal_path() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_path(const std::string& value); + std::string* _internal_mutable_path(); + public: + + // .mavsdk.rpc.log_files.Entry entry = 1; + bool has_entry() const; + private: + bool _internal_has_entry() const; + public: + void clear_entry(); + const ::mavsdk::rpc::log_files::Entry& entry() const; + PROTOBUF_MUST_USE_RESULT ::mavsdk::rpc::log_files::Entry* release_entry(); + ::mavsdk::rpc::log_files::Entry* mutable_entry(); + void set_allocated_entry(::mavsdk::rpc::log_files::Entry* entry); + private: + const ::mavsdk::rpc::log_files::Entry& _internal_entry() const; + ::mavsdk::rpc::log_files::Entry* _internal_mutable_entry(); + public: + void unsafe_arena_set_allocated_entry( + ::mavsdk::rpc::log_files::Entry* entry); + ::mavsdk::rpc::log_files::Entry* unsafe_arena_release_entry(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_files.DownloadLogFileRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr path_; + ::mavsdk::rpc::log_files::Entry* entry_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_log_5ffiles_2flog_5ffiles_2eproto; +}; +// ------------------------------------------------------------------- + +class EraseAllLogFilesRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_files.EraseAllLogFilesRequest) */ { + public: + inline EraseAllLogFilesRequest() : EraseAllLogFilesRequest(nullptr) {} + ~EraseAllLogFilesRequest() override; + explicit constexpr EraseAllLogFilesRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + EraseAllLogFilesRequest(const EraseAllLogFilesRequest& from); + EraseAllLogFilesRequest(EraseAllLogFilesRequest&& from) noexcept + : EraseAllLogFilesRequest() { + *this = ::std::move(from); + } + + inline EraseAllLogFilesRequest& operator=(const EraseAllLogFilesRequest& from) { + CopyFrom(from); + return *this; + } + inline EraseAllLogFilesRequest& operator=(EraseAllLogFilesRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const EraseAllLogFilesRequest& default_instance() { + return *internal_default_instance(); + } + static inline const EraseAllLogFilesRequest* internal_default_instance() { + return reinterpret_cast( + &_EraseAllLogFilesRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + friend void swap(EraseAllLogFilesRequest& a, EraseAllLogFilesRequest& b) { + a.Swap(&b); + } + inline void Swap(EraseAllLogFilesRequest* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(EraseAllLogFilesRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline EraseAllLogFilesRequest* New() const final { + return new EraseAllLogFilesRequest(); + } + + EraseAllLogFilesRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const EraseAllLogFilesRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const EraseAllLogFilesRequest& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(EraseAllLogFilesRequest* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.log_files.EraseAllLogFilesRequest"; + } + protected: + explicit EraseAllLogFilesRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_files.EraseAllLogFilesRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_log_5ffiles_2flog_5ffiles_2eproto; +}; +// ------------------------------------------------------------------- + +class EraseAllLogFilesResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_files.EraseAllLogFilesResponse) */ { + public: + inline EraseAllLogFilesResponse() : EraseAllLogFilesResponse(nullptr) {} + ~EraseAllLogFilesResponse() override; + explicit constexpr EraseAllLogFilesResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + EraseAllLogFilesResponse(const EraseAllLogFilesResponse& from); + EraseAllLogFilesResponse(EraseAllLogFilesResponse&& from) noexcept + : EraseAllLogFilesResponse() { + *this = ::std::move(from); + } + + inline EraseAllLogFilesResponse& operator=(const EraseAllLogFilesResponse& from) { + CopyFrom(from); + return *this; + } + inline EraseAllLogFilesResponse& operator=(EraseAllLogFilesResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const EraseAllLogFilesResponse& default_instance() { + return *internal_default_instance(); + } + static inline const EraseAllLogFilesResponse* internal_default_instance() { + return reinterpret_cast( + &_EraseAllLogFilesResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + friend void swap(EraseAllLogFilesResponse& a, EraseAllLogFilesResponse& b) { + a.Swap(&b); + } + inline void Swap(EraseAllLogFilesResponse* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(EraseAllLogFilesResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline EraseAllLogFilesResponse* New() const final { + return new EraseAllLogFilesResponse(); + } + + EraseAllLogFilesResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const EraseAllLogFilesResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const EraseAllLogFilesResponse& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(EraseAllLogFilesResponse* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.log_files.EraseAllLogFilesResponse"; + } + protected: + explicit EraseAllLogFilesResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kLogFilesResultFieldNumber = 1, + }; + // .mavsdk.rpc.log_files.LogFilesResult log_files_result = 1; + bool has_log_files_result() const; + private: + bool _internal_has_log_files_result() const; + public: + void clear_log_files_result(); + const ::mavsdk::rpc::log_files::LogFilesResult& log_files_result() const; + PROTOBUF_MUST_USE_RESULT ::mavsdk::rpc::log_files::LogFilesResult* release_log_files_result(); + ::mavsdk::rpc::log_files::LogFilesResult* mutable_log_files_result(); + void set_allocated_log_files_result(::mavsdk::rpc::log_files::LogFilesResult* log_files_result); + private: + const ::mavsdk::rpc::log_files::LogFilesResult& _internal_log_files_result() const; + ::mavsdk::rpc::log_files::LogFilesResult* _internal_mutable_log_files_result(); + public: + void unsafe_arena_set_allocated_log_files_result( + ::mavsdk::rpc::log_files::LogFilesResult* log_files_result); + ::mavsdk::rpc::log_files::LogFilesResult* unsafe_arena_release_log_files_result(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.log_files.EraseAllLogFilesResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::log_files::LogFilesResult* log_files_result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_log_5ffiles_2flog_5ffiles_2eproto; +}; +// ------------------------------------------------------------------- + class ProgressData final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.log_files.ProgressData) */ { public: @@ -798,7 +1248,7 @@ class ProgressData final : &_ProgressData_default_instance_); } static constexpr int kIndexInFileMessages = - 4; + 7; friend void swap(ProgressData& a, ProgressData& b) { a.Swap(&b); @@ -937,7 +1387,7 @@ class Entry final : &_Entry_default_instance_); } static constexpr int kIndexInFileMessages = - 5; + 8; friend void swap(Entry& a, Entry& b) { a.Swap(&b); @@ -1103,7 +1553,7 @@ class LogFilesResult final : &_LogFilesResult_default_instance_); } static constexpr int kIndexInFileMessages = - 6; + 9; friend void swap(LogFilesResult& a, LogFilesResult& b) { a.Swap(&b); @@ -1725,6 +2175,244 @@ inline void DownloadLogFileResponse::set_allocated_progress(::mavsdk::rpc::log_f // ------------------------------------------------------------------- +// DownloadLogFileRequest + +// .mavsdk.rpc.log_files.Entry entry = 1; +inline bool DownloadLogFileRequest::_internal_has_entry() const { + return this != internal_default_instance() && entry_ != nullptr; +} +inline bool DownloadLogFileRequest::has_entry() const { + return _internal_has_entry(); +} +inline void DownloadLogFileRequest::clear_entry() { + if (GetArenaForAllocation() == nullptr && entry_ != nullptr) { + delete entry_; + } + entry_ = nullptr; +} +inline const ::mavsdk::rpc::log_files::Entry& DownloadLogFileRequest::_internal_entry() const { + const ::mavsdk::rpc::log_files::Entry* p = entry_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::log_files::_Entry_default_instance_); +} +inline const ::mavsdk::rpc::log_files::Entry& DownloadLogFileRequest::entry() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_files.DownloadLogFileRequest.entry) + return _internal_entry(); +} +inline void DownloadLogFileRequest::unsafe_arena_set_allocated_entry( + ::mavsdk::rpc::log_files::Entry* entry) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(entry_); + } + entry_ = entry; + if (entry) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.log_files.DownloadLogFileRequest.entry) +} +inline ::mavsdk::rpc::log_files::Entry* DownloadLogFileRequest::release_entry() { + + ::mavsdk::rpc::log_files::Entry* temp = entry_; + entry_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::log_files::Entry* DownloadLogFileRequest::unsafe_arena_release_entry() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.log_files.DownloadLogFileRequest.entry) + + ::mavsdk::rpc::log_files::Entry* temp = entry_; + entry_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::log_files::Entry* DownloadLogFileRequest::_internal_mutable_entry() { + + if (entry_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::log_files::Entry>(GetArenaForAllocation()); + entry_ = p; + } + return entry_; +} +inline ::mavsdk::rpc::log_files::Entry* DownloadLogFileRequest::mutable_entry() { + ::mavsdk::rpc::log_files::Entry* _msg = _internal_mutable_entry(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.log_files.DownloadLogFileRequest.entry) + return _msg; +} +inline void DownloadLogFileRequest::set_allocated_entry(::mavsdk::rpc::log_files::Entry* entry) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete entry_; + } + if (entry) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::log_files::Entry>::GetOwningArena(entry); + if (message_arena != submessage_arena) { + entry = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, entry, submessage_arena); + } + + } else { + + } + entry_ = entry; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.log_files.DownloadLogFileRequest.entry) +} + +// string path = 2; +inline void DownloadLogFileRequest::clear_path() { + path_.ClearToEmpty(); +} +inline const std::string& DownloadLogFileRequest::path() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_files.DownloadLogFileRequest.path) + return _internal_path(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void DownloadLogFileRequest::set_path(ArgT0&& arg0, ArgT... args) { + + path_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.log_files.DownloadLogFileRequest.path) +} +inline std::string* DownloadLogFileRequest::mutable_path() { + std::string* _s = _internal_mutable_path(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.log_files.DownloadLogFileRequest.path) + return _s; +} +inline const std::string& DownloadLogFileRequest::_internal_path() const { + return path_.Get(); +} +inline void DownloadLogFileRequest::_internal_set_path(const std::string& value) { + + path_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* DownloadLogFileRequest::_internal_mutable_path() { + + return path_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* DownloadLogFileRequest::release_path() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.log_files.DownloadLogFileRequest.path) + return path_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void DownloadLogFileRequest::set_allocated_path(std::string* path) { + if (path != nullptr) { + + } else { + + } + path_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), path, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.log_files.DownloadLogFileRequest.path) +} + +// ------------------------------------------------------------------- + +// EraseAllLogFilesRequest + +// ------------------------------------------------------------------- + +// EraseAllLogFilesResponse + +// .mavsdk.rpc.log_files.LogFilesResult log_files_result = 1; +inline bool EraseAllLogFilesResponse::_internal_has_log_files_result() const { + return this != internal_default_instance() && log_files_result_ != nullptr; +} +inline bool EraseAllLogFilesResponse::has_log_files_result() const { + return _internal_has_log_files_result(); +} +inline void EraseAllLogFilesResponse::clear_log_files_result() { + if (GetArenaForAllocation() == nullptr && log_files_result_ != nullptr) { + delete log_files_result_; + } + log_files_result_ = nullptr; +} +inline const ::mavsdk::rpc::log_files::LogFilesResult& EraseAllLogFilesResponse::_internal_log_files_result() const { + const ::mavsdk::rpc::log_files::LogFilesResult* p = log_files_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::log_files::_LogFilesResult_default_instance_); +} +inline const ::mavsdk::rpc::log_files::LogFilesResult& EraseAllLogFilesResponse::log_files_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.log_files.EraseAllLogFilesResponse.log_files_result) + return _internal_log_files_result(); +} +inline void EraseAllLogFilesResponse::unsafe_arena_set_allocated_log_files_result( + ::mavsdk::rpc::log_files::LogFilesResult* log_files_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(log_files_result_); + } + log_files_result_ = log_files_result; + if (log_files_result) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.log_files.EraseAllLogFilesResponse.log_files_result) +} +inline ::mavsdk::rpc::log_files::LogFilesResult* EraseAllLogFilesResponse::release_log_files_result() { + + ::mavsdk::rpc::log_files::LogFilesResult* temp = log_files_result_; + log_files_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::log_files::LogFilesResult* EraseAllLogFilesResponse::unsafe_arena_release_log_files_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.log_files.EraseAllLogFilesResponse.log_files_result) + + ::mavsdk::rpc::log_files::LogFilesResult* temp = log_files_result_; + log_files_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::log_files::LogFilesResult* EraseAllLogFilesResponse::_internal_mutable_log_files_result() { + + if (log_files_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::log_files::LogFilesResult>(GetArenaForAllocation()); + log_files_result_ = p; + } + return log_files_result_; +} +inline ::mavsdk::rpc::log_files::LogFilesResult* EraseAllLogFilesResponse::mutable_log_files_result() { + ::mavsdk::rpc::log_files::LogFilesResult* _msg = _internal_mutable_log_files_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.log_files.EraseAllLogFilesResponse.log_files_result) + return _msg; +} +inline void EraseAllLogFilesResponse::set_allocated_log_files_result(::mavsdk::rpc::log_files::LogFilesResult* log_files_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete log_files_result_; + } + if (log_files_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::log_files::LogFilesResult>::GetOwningArena(log_files_result); + if (message_arena != submessage_arena) { + log_files_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, log_files_result, submessage_arena); + } + + } else { + + } + log_files_result_ = log_files_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.log_files.EraseAllLogFilesResponse.log_files_result) +} + +// ------------------------------------------------------------------- + // ProgressData // float progress = 1 [(.mavsdk.options.default_value) = "NaN"]; @@ -1922,6 +2610,12 @@ inline void LogFilesResult::set_allocated_result_str(std::string* result_str) { // ------------------------------------------------------------------- +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + // @@protoc_insertion_point(namespace_scope) diff --git a/src/mavsdk_server/src/plugins/log_files/log_files_service_impl.h b/src/mavsdk_server/src/plugins/log_files/log_files_service_impl.h index ef5d2f9f9c..12e5e15d62 100644 --- a/src/mavsdk_server/src/plugins/log_files/log_files_service_impl.h +++ b/src/mavsdk_server/src/plugins/log_files/log_files_service_impl.h @@ -220,6 +220,60 @@ class LogFilesServiceImpl final : public rpc::log_files::LogFilesService::Servic return grpc::Status::OK; } + grpc::Status DownloadLogFile( + grpc::ServerContext* /* context */, + const rpc::log_files::DownloadLogFileRequest* request, + rpc::log_files::DownloadLogFileResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::LogFiles::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "DownloadLogFile sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->download_log_file( + translateFromRpcEntry(request->entry()), request->path()); + + if (response != nullptr) { + fillResponseWithResult(response, result.first); + + response->set_allocated_progress(translateToRpcProgressData(result.second).release()); + } + + return grpc::Status::OK; + } + + grpc::Status EraseAllLogFiles( + grpc::ServerContext* /* context */, + const rpc::log_files::EraseAllLogFilesRequest* /* request */, + rpc::log_files::EraseAllLogFilesResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::LogFiles::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->erase_all_log_files(); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + void stop() { _stopped.store(true);