diff --git a/proto b/proto index 11769a4ee6..a48be863e7 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 11769a4ee6f3f9b0fef71532f773d40ab3e7d55c +Subproject commit a48be863e7204629d7b690dfc01161f39889f87e diff --git a/src/mavsdk/core/CMakeLists.txt b/src/mavsdk/core/CMakeLists.txt index 98b19043cc..1be3f278f6 100644 --- a/src/mavsdk/core/CMakeLists.txt +++ b/src/mavsdk/core/CMakeLists.txt @@ -23,6 +23,7 @@ target_sources(mavsdk mavlink_mission_transfer.cpp mavlink_parameters.cpp mavlink_receiver.cpp + mavlink_request_message_handler.cpp mavlink_statustext_handler.cpp mavlink_message_handler.cpp ping.cpp diff --git a/src/mavsdk/core/mavlink_request_message_handler.cpp b/src/mavsdk/core/mavlink_request_message_handler.cpp new file mode 100644 index 0000000000..e39aa3ec5b --- /dev/null +++ b/src/mavsdk/core/mavlink_request_message_handler.cpp @@ -0,0 +1,126 @@ +#include "mavlink_request_message_handler.h" +#include "system_impl.h" + +namespace mavsdk { + +MavlinkRequestMessageHandler::MavlinkRequestMessageHandler(SystemImpl& system_impl) : + _system_impl(system_impl) +{ + _system_impl.register_mavlink_command_handler( + MAV_CMD_REQUEST_MESSAGE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return handle_command_long(command); + }, + this); + + _system_impl.register_mavlink_command_handler( + MAV_CMD_REQUEST_MESSAGE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return handle_command_long(command); + }, + this); +} + +MavlinkRequestMessageHandler::~MavlinkRequestMessageHandler() +{ + _system_impl.unregister_all_mavlink_message_handlers(this); +} + +bool MavlinkRequestMessageHandler::register_handler( + uint32_t message_id, const Callback& callback, const void* cookie) +{ + std::lock_guard lock(_table_mutex); + + if (std::find_if(_table.begin(), _table.end(), [message_id](const Entry& entry) { + return entry.message_id == message_id; + }) != _table.end()) { + LogErr() << "message id " << message_id << " already registered, registration ignored"; + return false; + } + + _table.emplace_back(Entry{message_id, callback, cookie}); + return true; +} + +void MavlinkRequestMessageHandler::unregister_handler(uint32_t message_id, const void* cookie) +{ + std::lock_guard lock(_table_mutex); + + _table.erase( + std::remove_if( + _table.begin(), + _table.end(), + [&message_id, &cookie](const Entry& entry) { + return entry.message_id == message_id && entry.cookie == cookie; + }), + _table.end()); +} + +void MavlinkRequestMessageHandler::unregister_all_handlers(const void* cookie) +{ + std::lock_guard lock(_table_mutex); + + _table.erase( + std::remove_if( + _table.begin(), + _table.end(), + [&cookie](const Entry& entry) { return entry.cookie == cookie; }), + _table.end()); +} + +std::optional MavlinkRequestMessageHandler::handle_command_long( + const MavlinkCommandReceiver::CommandLong& command) +{ + std::lock_guard lock(_table_mutex); + + for (auto& entry : _table) { + if (entry.message_id == static_cast(std::round(command.params.param1))) { + if (entry.callback != nullptr) { + const auto result = entry.callback( + {command.params.param2, + command.params.param3, + command.params.param4, + command.params.param5, + command.params.param6}); + + if (result.has_value()) { + return _system_impl.make_command_ack_message(command, result.value()); + } + } + return {}; + } + } + + // We could respond with MAV_RESULT_UNSUPPORTED here, however, it's not clear if maybe someone + // else might be answering the command. + + return {}; +} + +std::optional +MavlinkRequestMessageHandler::handle_command_int(const MavlinkCommandReceiver::CommandInt& command) +{ + std::lock_guard lock(_table_mutex); + + for (auto& entry : _table) { + if (entry.message_id == static_cast(std::round(command.params.param1))) { + if (entry.callback != nullptr) { + const auto result = entry.callback( + {command.params.param2, + command.params.param3, + command.params.param4, + static_cast(command.params.x), + static_cast(command.params.y)}); + + if (result.has_value()) { + return _system_impl.make_command_ack_message(command, result.value()); + } + } + return {}; + } + } + + return {}; +} + +} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_request_message_handler.h b/src/mavsdk/core/mavlink_request_message_handler.h new file mode 100644 index 0000000000..521e5234c1 --- /dev/null +++ b/src/mavsdk/core/mavlink_request_message_handler.h @@ -0,0 +1,46 @@ +#pragma once + +#include +#include +#include +#include +#include +#include "mavlink_include.h" +#include "mavlink_command_receiver.h" + +namespace mavsdk { + +class SystemImpl; + +class MavlinkRequestMessageHandler { +public: + MavlinkRequestMessageHandler() = delete; + explicit MavlinkRequestMessageHandler(SystemImpl& system_impl); + ~MavlinkRequestMessageHandler(); + + using Params = std::array; + using Callback = std::function(Params)>; + + bool register_handler(uint32_t message_id, const Callback& callback, const void* cookie); + void unregister_handler(uint32_t message_id, const void* cookie); + void unregister_all_handlers(const void* cookie); + +private: + std::optional + handle_command_long(const MavlinkCommandReceiver::CommandLong& command); + std::optional + handle_command_int(const MavlinkCommandReceiver::CommandInt& command); + + struct Entry { + uint32_t message_id; + Callback callback; + const void* cookie; + }; + + std::mutex _table_mutex{}; + std::vector _table{}; + + SystemImpl& _system_impl; +}; + +} // namespace mavsdk diff --git a/src/mavsdk/core/system_impl.cpp b/src/mavsdk/core/system_impl.cpp index df91f004e7..0fbca8460b 100644 --- a/src/mavsdk/core/system_impl.cpp +++ b/src/mavsdk/core/system_impl.cpp @@ -22,6 +22,7 @@ SystemImpl::SystemImpl(MavsdkImpl& parent) : _params(*this), _command_sender(*this), _command_receiver(*this), + _request_message_handler(*this), _timesync(*this), _ping(*this), _mission_transfer( @@ -80,14 +81,6 @@ void SystemImpl::init(uint8_t system_id, uint8_t comp_id, bool connected) }, this); - // TO-DO! - register_mavlink_command_handler( - MAV_CMD_REQUEST_MESSAGE, - [this](const MavlinkCommandReceiver::CommandLong& command) { - return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); - }, - this); - add_new_component(comp_id); } @@ -1605,6 +1598,22 @@ void SystemImpl::unregister_all_mavlink_command_handlers(const void* cookie) _command_receiver.unregister_all_mavlink_command_handlers(cookie); } +bool SystemImpl::register_mavlink_request_message_handler( + uint32_t message_id, const MavlinkRequestMessageHandler::Callback& callback, const void* cookie) +{ + return _request_message_handler.register_handler(message_id, callback, cookie); +} + +void SystemImpl::unregister_mavlink_request_message_handler(uint32_t message_id, const void* cookie) +{ + _request_message_handler.unregister_handler(message_id, cookie); +} + +void SystemImpl::unregister_mavlink_request_message_handler(const void* cookie) +{ + _request_message_handler.unregister_all_handlers(cookie); +} + void SystemImpl::set_server_armed(bool armed) { uint8_t base_mode = _parent.get_base_mode(); diff --git a/src/mavsdk/core/system_impl.h b/src/mavsdk/core/system_impl.h index 184bbac9a3..5b973265fb 100644 --- a/src/mavsdk/core/system_impl.h +++ b/src/mavsdk/core/system_impl.h @@ -8,6 +8,7 @@ #include "mavlink_command_sender.h" #include "mavlink_message_handler.h" #include "mavlink_mission_transfer.h" +#include "mavlink_request_message_handler.h" #include "mavlink_statustext_handler.h" #include "request_message.h" #include "ardupilot_custom_mode.h" @@ -276,6 +277,13 @@ class SystemImpl : public Sender { void unregister_mavlink_command_handler(uint16_t cmd_id, const void* cookie); void unregister_all_mavlink_command_handlers(const void* cookie); + bool register_mavlink_request_message_handler( + uint32_t message_id, + const MavlinkRequestMessageHandler::Callback& callback, + const void* cookie); + void unregister_mavlink_request_message_handler(uint32_t message_id, const void* cookie); + void unregister_mavlink_request_message_handler(const void* cookie); + double timeout_s() const; // Autopilot version data @@ -386,6 +394,7 @@ class SystemImpl : public Sender { MAVLinkParameters _params; MavlinkCommandSender _command_sender; MavlinkCommandReceiver _command_receiver; + MavlinkRequestMessageHandler _request_message_handler; Timesync _timesync; Ping _ping; diff --git a/src/mavsdk/plugins/CMakeLists.txt b/src/mavsdk/plugins/CMakeLists.txt index 7141a16474..91d69ac547 100644 --- a/src/mavsdk/plugins/CMakeLists.txt +++ b/src/mavsdk/plugins/CMakeLists.txt @@ -24,6 +24,7 @@ add_subdirectory(tracking_server) add_subdirectory(server_utility) add_subdirectory(transponder) add_subdirectory(telemetry_server) +add_subdirectory(component_information_server) add_subdirectory(tune) set(UNIT_TEST_SOURCES ${UNIT_TEST_SOURCES} PARENT_SCOPE) diff --git a/src/mavsdk/plugins/component_information_server/CMakeLists.txt b/src/mavsdk/plugins/component_information_server/CMakeLists.txt new file mode 100644 index 0000000000..7ca53752eb --- /dev/null +++ b/src/mavsdk/plugins/component_information_server/CMakeLists.txt @@ -0,0 +1,15 @@ +target_sources(mavsdk + PRIVATE + component_information_server.cpp + component_information_server_impl.cpp +) + +target_include_directories(mavsdk PUBLIC + $ + $ + ) + +install(FILES + include/plugins/component_information_server/component_information_server.h + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/mavsdk/plugins/component_information_server +) \ No newline at end of file diff --git a/src/mavsdk/plugins/component_information_server/component_information_server.cpp b/src/mavsdk/plugins/component_information_server/component_information_server.cpp new file mode 100644 index 0000000000..010cf44ee3 --- /dev/null +++ b/src/mavsdk/plugins/component_information_server/component_information_server.cpp @@ -0,0 +1,53 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see +// https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/component_information_server/component_information_server.proto) + +#include + +#include "component_information_server_impl.h" +#include "plugins/component_information_server/component_information_server.h" + +namespace mavsdk { + +ComponentInformationServer::ComponentInformationServer(System& system) : + PluginBase(), + _impl{std::make_unique(system)} +{} + +ComponentInformationServer::ComponentInformationServer(std::shared_ptr system) : + PluginBase(), + _impl{std::make_unique(system)} +{} + +ComponentInformationServer::~ComponentInformationServer() {} + +ComponentInformationServer::Result +ComponentInformationServer::provide_peripheral_file(std::string path) const +{ + return _impl->provide_peripheral_file(path); +} + +std::ostream& operator<<(std::ostream& str, ComponentInformationServer::Result const& result) +{ + switch (result) { + case ComponentInformationServer::Result::Unknown: + return str << "Unknown"; + case ComponentInformationServer::Result::Success: + return str << "Success"; + case ComponentInformationServer::Result::NotFound: + return str << "Not Found"; + case ComponentInformationServer::Result::OpenFailure: + return str << "Open Failure"; + case ComponentInformationServer::Result::ReadFailure: + return str << "Read Failure"; + case ComponentInformationServer::Result::FailedJsonParsing: + return str << "Failed Json Parsing"; + case ComponentInformationServer::Result::FailedJsonSchema: + return str << "Failed Json Schema"; + default: + return str << "Unknown"; + } +} + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/component_information_server/component_information_server_impl.cpp b/src/mavsdk/plugins/component_information_server/component_information_server_impl.cpp new file mode 100644 index 0000000000..e75b102e9d --- /dev/null +++ b/src/mavsdk/plugins/component_information_server/component_information_server_impl.cpp @@ -0,0 +1,96 @@ +#include "component_information_server_impl.h" +#include "mavlink_request_message_handler.h" +#include "fs.h" +#include "crc32.h" +#include +#include + +namespace mavsdk { + +ComponentInformationServerImpl::ComponentInformationServerImpl(System& system) : + PluginImplBase(system) +{ + _parent->register_plugin(this); +} + +ComponentInformationServerImpl::ComponentInformationServerImpl(std::shared_ptr system) : + PluginImplBase(std::move(system)) +{ + _parent->register_plugin(this); +} + +ComponentInformationServerImpl::~ComponentInformationServerImpl() +{ + _parent->unregister_plugin(this); +} + +void ComponentInformationServerImpl::init() {} + +void ComponentInformationServerImpl::deinit() +{ + _parent->unregister_all_mavlink_message_handlers(this); +} + +void ComponentInformationServerImpl::enable() {} + +void ComponentInformationServerImpl::disable() {} + +ComponentInformationServer::Result +ComponentInformationServerImpl::provide_peripheral_file(const std::string& path) +{ + if (!fs_exists(path)) { + return ComponentInformationServer::Result::NotFound; + } + + _path = path; + + std::ifstream file(path, std::ios::binary); + + if (!file) { + return ComponentInformationServer::Result::OpenFailure; + } + + file.seekg(0, std::ifstream::end); + auto length = file.tellg(); + file.seekg(0, std::ifstream::beg); + + std::string buf; + buf.reserve(length); + file.read(buf.data(), length); + + if (!file) { + return ComponentInformationServer::Result::ReadFailure; + } + + Crc32 crc32_calculator; + crc32_calculator.add(reinterpret_cast(buf.data()), buf.length()); + _crc32 = crc32_calculator.get(); + + _parent->register_mavlink_request_message_handler( + MAVLINK_MSG_ID_COMPONENT_INFORMATION, + [this](MavlinkRequestMessageHandler::Params) { + return process_component_information_requested(); + }, + this); + + return ComponentInformationServer::Result::Success; +} + +std::optional ComponentInformationServerImpl::process_component_information_requested() +{ + mavlink_message_t message; + mavlink_msg_component_information_pack( + _parent->get_own_system_id(), + _parent->get_own_component_id(), + &message, + _parent->get_time().elapsed_ms(), + 0, + "", + _crc32, + _path.c_str()); + _parent->send_message(message); + + return MAV_RESULT_ACCEPTED; +} + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_information_server/component_information_server_impl.h b/src/mavsdk/plugins/component_information_server/component_information_server_impl.h new file mode 100644 index 0000000000..a7be90f28d --- /dev/null +++ b/src/mavsdk/plugins/component_information_server/component_information_server_impl.h @@ -0,0 +1,29 @@ +#pragma once + +#include "plugins/component_information_server/component_information_server.h" +#include "plugin_impl_base.h" + +namespace mavsdk { + +class ComponentInformationServerImpl : public PluginImplBase { +public: + explicit ComponentInformationServerImpl(System& system); + explicit ComponentInformationServerImpl(std::shared_ptr system); + ~ComponentInformationServerImpl(); + + void init() override; + void deinit() override; + + void enable() override; + void disable() override; + + ComponentInformationServer::Result provide_peripheral_file(const std::string& path); + +private: + std::optional process_component_information_requested(); + + std::string _path{}; + uint32_t _crc32{0}; +}; + +} // namespace mavsdk diff --git a/src/mavsdk/plugins/component_information_server/include/plugins/component_information_server/component_information_server.h b/src/mavsdk/plugins/component_information_server/include/plugins/component_information_server/component_information_server.h new file mode 100644 index 0000000000..9383eeea35 --- /dev/null +++ b/src/mavsdk/plugins/component_information_server/include/plugins/component_information_server/component_information_server.h @@ -0,0 +1,110 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see +// https://github.com/mavlink/MAVSDK-Proto/blob/main/protos/component_information_server/component_information_server.proto) + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "plugin_base.h" + +namespace mavsdk { + +class System; +class ComponentInformationServerImpl; + +/** + * @brief Provide raw access to retrieve and provide server parameters. + */ +class ComponentInformationServer : public PluginBase { +public: + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto component_information_server = ComponentInformationServer(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit ComponentInformationServer(System& system); // deprecated + + /** + * @brief Constructor. Creates the plugin for a specific System. + * + * The plugin is typically created as shown below: + * + * ```cpp + * auto component_information_server = ComponentInformationServer(system); + * ``` + * + * @param system The specific system associated with this plugin. + */ + explicit ComponentInformationServer(std::shared_ptr system); // new + + /** + * @brief Destructor (internal use only). + */ + ~ComponentInformationServer(); + + /** + * @brief Possible results returned for param requests. + */ + enum class Result { + Unknown, /**< @brief Unknown result. */ + Success, /**< @brief Request succeeded. */ + NotFound, /**< @brief Not Found. */ + OpenFailure, /**< @brief Failure trying to open. */ + ReadFailure, /**< @brief Failure trying to read. */ + FailedJsonParsing, /**< @brief JSON parsing error. */ + FailedJsonSchema, /**< @brief JSON schema error. */ + }; + + /** + * @brief Stream operator to print information about a `ComponentInformationServer::Result`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, ComponentInformationServer::Result const& result); + + /** + * @brief Callback type for asynchronous ComponentInformationServer calls. + */ + using ResultCallback = std::function; + + /** + * @brief Provide a component information JSON file. + * + * This function is blocking. + * + * @return Result of request. + */ + Result provide_peripheral_file(std::string path) const; + + /** + * @brief Copy constructor. + */ + ComponentInformationServer(const ComponentInformationServer& other); + + /** + * @brief Equality operator (object is not copyable). + */ + const ComponentInformationServer& operator=(const ComponentInformationServer&) = delete; + +private: + /** @private Underlying implementation, set at instantiation */ + std::unique_ptr _impl; +}; + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.cc b/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.cc new file mode 100644 index 0000000000..567a22b198 --- /dev/null +++ b/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.cc @@ -0,0 +1,90 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: component_information_server/component_information_server.proto + +#include "component_information_server/component_information_server.pb.h" +#include "component_information_server/component_information_server.grpc.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +namespace mavsdk { +namespace rpc { +namespace component_information_server { + +static const char* ComponentInformationServerService_method_names[] = { + "/mavsdk.rpc.component_information_server.ComponentInformationServerService/ProvidePeripheralFile", +}; + +std::unique_ptr< ComponentInformationServerService::Stub> ComponentInformationServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { + (void)options; + std::unique_ptr< ComponentInformationServerService::Stub> stub(new ComponentInformationServerService::Stub(channel, options)); + return stub; +} + +ComponentInformationServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) + : channel_(channel), rpcmethod_ProvidePeripheralFile_(ComponentInformationServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + {} + +::grpc::Status ComponentInformationServerService::Stub::ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_ProvidePeripheralFile_, context, request, response); +} + +void ComponentInformationServerService::Stub::async::ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ProvidePeripheralFile_, context, request, response, std::move(f)); +} + +void ComponentInformationServerService::Stub::async::ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ProvidePeripheralFile_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* ComponentInformationServerService::Stub::PrepareAsyncProvidePeripheralFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_ProvidePeripheralFile_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* ComponentInformationServerService::Stub::AsyncProvidePeripheralFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncProvidePeripheralFileRaw(context, request, cq); + result->StartCall(); + return result; +} + +ComponentInformationServerService::Service::Service() { + AddMethod(new ::grpc::internal::RpcServiceMethod( + ComponentInformationServerService_method_names[0], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< ComponentInformationServerService::Service, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](ComponentInformationServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* req, + ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* resp) { + return service->ProvidePeripheralFile(ctx, req, resp); + }, this))); +} + +ComponentInformationServerService::Service::~Service() { +} + +::grpc::Status ComponentInformationServerService::Service::ProvidePeripheralFile(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + + +} // namespace mavsdk +} // namespace rpc +} // namespace component_information_server + diff --git a/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.h b/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.h new file mode 100644 index 0000000000..95c7528c5f --- /dev/null +++ b/src/mavsdk_server/src/generated/component_information_server/component_information_server.grpc.pb.h @@ -0,0 +1,251 @@ +// Generated by the gRPC C++ plugin. +// If you make any local change, they will be lost. +// source: component_information_server/component_information_server.proto +#ifndef GRPC_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto__INCLUDED +#define GRPC_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto__INCLUDED + +#include "component_information_server/component_information_server.pb.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace rpc { +namespace component_information_server { + +// Provide raw access to retrieve and provide server parameters. +class ComponentInformationServerService final { + public: + static constexpr char const* service_full_name() { + return "mavsdk.rpc.component_information_server.ComponentInformationServerService"; + } + class StubInterface { + public: + virtual ~StubInterface() {} + // + // Provide a component information JSON file. + virtual ::grpc::Status ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>> AsyncProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>>(AsyncProvidePeripheralFileRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>> PrepareAsyncProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>>(PrepareAsyncProvidePeripheralFileRaw(context, request, cq)); + } + class async_interface { + public: + virtual ~async_interface() {} + // + // Provide a component information JSON file. + virtual void ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response, std::function) = 0; + virtual void ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + }; + typedef class async_interface experimental_async_interface; + virtual class async_interface* async() { return nullptr; } + class async_interface* experimental_async() { return async(); } + private: + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* AsyncProvidePeripheralFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* PrepareAsyncProvidePeripheralFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) = 0; + }; + class Stub final : public StubInterface { + public: + Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + ::grpc::Status ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>> AsyncProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>>(AsyncProvidePeripheralFileRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>> PrepareAsyncProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>>(PrepareAsyncProvidePeripheralFileRaw(context, request, cq)); + } + class async final : + public StubInterface::async_interface { + public: + void ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response, std::function) override; + void ProvidePeripheralFile(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + private: + friend class Stub; + explicit async(Stub* stub): stub_(stub) { } + Stub* stub() { return stub_; } + Stub* stub_; + }; + class async* async() override { return &async_stub_; } + + private: + std::shared_ptr< ::grpc::ChannelInterface> channel_; + class async async_stub_{this}; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* AsyncProvidePeripheralFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* PrepareAsyncProvidePeripheralFileRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest& request, ::grpc::CompletionQueue* cq) override; + const ::grpc::internal::RpcMethod rpcmethod_ProvidePeripheralFile_; + }; + static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + + class Service : public ::grpc::Service { + public: + Service(); + virtual ~Service(); + // + // Provide a component information JSON file. + virtual ::grpc::Status ProvidePeripheralFile(::grpc::ServerContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response); + }; + template + class WithAsyncMethod_ProvidePeripheralFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_ProvidePeripheralFile() { + ::grpc::Service::MarkMethodAsync(0); + } + ~WithAsyncMethod_ProvidePeripheralFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ProvidePeripheralFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestProvidePeripheralFile(::grpc::ServerContext* context, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_ProvidePeripheralFile AsyncService; + template + class WithCallbackMethod_ProvidePeripheralFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_ProvidePeripheralFile() { + ::grpc::Service::MarkMethodCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* request, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* response) { return this->ProvidePeripheralFile(context, request, response); }));} + void SetMessageAllocatorFor_ProvidePeripheralFile( + ::grpc::MessageAllocator< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_ProvidePeripheralFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ProvidePeripheralFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ProvidePeripheralFile( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_ProvidePeripheralFile CallbackService; + typedef CallbackService ExperimentalCallbackService; + template + class WithGenericMethod_ProvidePeripheralFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_ProvidePeripheralFile() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_ProvidePeripheralFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ProvidePeripheralFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithRawMethod_ProvidePeripheralFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ProvidePeripheralFile() { + ::grpc::Service::MarkMethodRaw(0); + } + ~WithRawMethod_ProvidePeripheralFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ProvidePeripheralFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestProvidePeripheralFile(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawCallbackMethod_ProvidePeripheralFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_ProvidePeripheralFile() { + ::grpc::Service::MarkMethodRawCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ProvidePeripheralFile(context, request, response); })); + } + ~WithRawCallbackMethod_ProvidePeripheralFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ProvidePeripheralFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ProvidePeripheralFile( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithStreamedUnaryMethod_ProvidePeripheralFile : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_ProvidePeripheralFile() { + ::grpc::Service::MarkMethodStreamed(0, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* streamer) { + return this->StreamedProvidePeripheralFile(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_ProvidePeripheralFile() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status ProvidePeripheralFile(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* /*request*/, ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedProvidePeripheralFile(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest,::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_ProvidePeripheralFile StreamedUnaryService; + typedef Service SplitStreamedService; + typedef WithStreamedUnaryMethod_ProvidePeripheralFile StreamedService; +}; + +} // namespace component_information_server +} // namespace rpc +} // namespace mavsdk + + +#endif // GRPC_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto__INCLUDED diff --git a/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.cc b/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.cc new file mode 100644 index 0000000000..53b5773a9a --- /dev/null +++ b/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.cc @@ -0,0 +1,823 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: component_information_server/component_information_server.proto + +#include "component_information_server/component_information_server.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +// @@protoc_insertion_point(includes) +#include + +PROTOBUF_PRAGMA_INIT_SEG +namespace mavsdk { +namespace rpc { +namespace component_information_server { +constexpr ProvidePeripheralFileRequest::ProvidePeripheralFileRequest( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : path_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string){} +struct ProvidePeripheralFileRequestDefaultTypeInternal { + constexpr ProvidePeripheralFileRequestDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~ProvidePeripheralFileRequestDefaultTypeInternal() {} + union { + ProvidePeripheralFileRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT ProvidePeripheralFileRequestDefaultTypeInternal _ProvidePeripheralFileRequest_default_instance_; +constexpr ProvidePeripheralFileResponse::ProvidePeripheralFileResponse( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : component_information_server_result_(nullptr){} +struct ProvidePeripheralFileResponseDefaultTypeInternal { + constexpr ProvidePeripheralFileResponseDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~ProvidePeripheralFileResponseDefaultTypeInternal() {} + union { + ProvidePeripheralFileResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT ProvidePeripheralFileResponseDefaultTypeInternal _ProvidePeripheralFileResponse_default_instance_; +constexpr ComponentInformationServerResult::ComponentInformationServerResult( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : result_str_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , result_(0) +{} +struct ComponentInformationServerResultDefaultTypeInternal { + constexpr ComponentInformationServerResultDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~ComponentInformationServerResultDefaultTypeInternal() {} + union { + ComponentInformationServerResult _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT ComponentInformationServerResultDefaultTypeInternal _ComponentInformationServerResult_default_instance_; +} // namespace component_information_server +} // namespace rpc +} // namespace mavsdk +static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[3]; +static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[1]; +static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto = nullptr; + +const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest, path_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse, component_information_server_result_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ComponentInformationServerResult, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ComponentInformationServerResult, result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_information_server::ComponentInformationServerResult, result_str_), +}; +static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest)}, + { 6, -1, sizeof(::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse)}, + { 12, -1, sizeof(::mavsdk::rpc::component_information_server::ComponentInformationServerResult)}, +}; + +static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = { + reinterpret_cast(&::mavsdk::rpc::component_information_server::_ProvidePeripheralFileRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::component_information_server::_ProvidePeripheralFileResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::component_information_server::_ComponentInformationServerResult_default_instance_), +}; + +const char descriptor_table_protodef_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = + "\n\?component_information_server/component" + "_information_server.proto\022\'mavsdk.rpc.co" + "mponent_information_server\032\024mavsdk_optio" + "ns.proto\",\n\034ProvidePeripheralFileRequest" + "\022\014\n\004path\030\001 \001(\t\"\227\001\n\035ProvidePeripheralFile" + "Response\022v\n#component_information_server" + "_result\030\001 \001(\0132I.mavsdk.rpc.component_inf" + "ormation_server.ComponentInformationServ" + "erResult\"\322\002\n ComponentInformationServerR" + "esult\022`\n\006result\030\001 \001(\0162P.mavsdk.rpc.compo" + "nent_information_server.ComponentInforma" + "tionServerResult.Result\022\022\n\nresult_str\030\002 " + "\001(\t\"\267\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RE" + "SULT_SUCCESS\020\001\022\024\n\020RESULT_NOT_FOUND\020\002\022\027\n\023" + "RESULT_OPEN_FAILURE\020\003\022\027\n\023RESULT_READ_FAI" + "LURE\020\004\022\036\n\032RESULT_FAILED_JSON_PARSING\020\005\022\035" + "\n\031RESULT_FAILED_JSON_SCHEMA\020\0062\322\001\n!Compon" + "entInformationServerService\022\254\001\n\025ProvideP" + "eripheralFile\022E.mavsdk.rpc.component_inf" + "ormation_server.ProvidePeripheralFileReq" + "uest\032F.mavsdk.rpc.component_information_" + "server.ProvidePeripheralFileResponse\"\004\200\265" + "\030\001BI\n&io.mavsdk.component_information_se" + "rverB\037ComponentInformationServerProtob\006p" + "roto3" + ; +static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_deps[1] = { + &::descriptor_table_mavsdk_5foptions_2eproto, +}; +static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once; +const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto = { + false, false, 965, descriptor_table_protodef_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto, "component_information_server/component_information_server.proto", + &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_deps, 1, 3, + schemas, file_default_instances, TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto::offsets, + file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto, file_level_enum_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto, file_level_service_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto, +}; +PROTOBUF_ATTRIBUTE_WEAK const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable* descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter() { + return &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; +} + +// Force running AddDescriptors() at dynamic initialization time. +PROTOBUF_ATTRIBUTE_INIT_PRIORITY static ::PROTOBUF_NAMESPACE_ID::internal::AddDescriptorsRunner dynamic_init_dummy_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto(&descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto); +namespace mavsdk { +namespace rpc { +namespace component_information_server { +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* ComponentInformationServerResult_Result_descriptor() { + ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto); + return file_level_enum_descriptors_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[0]; +} +bool ComponentInformationServerResult_Result_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + return true; + default: + return false; + } +} + +#if (__cplusplus < 201703) && (!defined(_MSC_VER) || _MSC_VER >= 1900) +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_UNKNOWN; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_SUCCESS; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_NOT_FOUND; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_OPEN_FAILURE; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_READ_FAILURE; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_FAILED_JSON_PARSING; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::RESULT_FAILED_JSON_SCHEMA; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::Result_MIN; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult::Result_MAX; +constexpr int ComponentInformationServerResult::Result_ARRAYSIZE; +#endif // (__cplusplus < 201703) && (!defined(_MSC_VER) || _MSC_VER >= 1900) + +// =================================================================== + +class ProvidePeripheralFileRequest::_Internal { + public: +}; + +ProvidePeripheralFileRequest::ProvidePeripheralFileRequest(::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.component_information_server.ProvidePeripheralFileRequest) +} +ProvidePeripheralFileRequest::ProvidePeripheralFileRequest(const ProvidePeripheralFileRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + path_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_path().empty()) { + path_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_path(), + GetArenaForAllocation()); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) +} + +inline void ProvidePeripheralFileRequest::SharedCtor() { +path_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +} + +ProvidePeripheralFileRequest::~ProvidePeripheralFileRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void ProvidePeripheralFileRequest::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + path_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +} + +void ProvidePeripheralFileRequest::ArenaDtor(void* object) { + ProvidePeripheralFileRequest* _this = reinterpret_cast< ProvidePeripheralFileRequest* >(object); + (void)_this; +} +void ProvidePeripheralFileRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void ProvidePeripheralFileRequest::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void ProvidePeripheralFileRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + path_.ClearToEmpty(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* ProvidePeripheralFileRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // string path = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + auto str = _internal_mutable_path(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest.path")); + 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* ProvidePeripheralFileRequest::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string path = 1; + 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.component_information_server.ProvidePeripheralFileRequest.path"); + target = stream->WriteStringMaybeAliased( + 1, 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.component_information_server.ProvidePeripheralFileRequest) + return target; +} + +size_t ProvidePeripheralFileRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) + 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 path = 1; + if (!this->_internal_path().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_path()); + } + + 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 ProvidePeripheralFileRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + ProvidePeripheralFileRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ProvidePeripheralFileRequest::GetClassData() const { return &_class_data_; } + +void ProvidePeripheralFileRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void ProvidePeripheralFileRequest::MergeFrom(const ProvidePeripheralFileRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_path().empty()) { + _internal_set_path(from._internal_path()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void ProvidePeripheralFileRequest::CopyFrom(const ProvidePeripheralFileRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ProvidePeripheralFileRequest::IsInitialized() const { + return true; +} + +void ProvidePeripheralFileRequest::InternalSwap(ProvidePeripheralFileRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &path_, GetArenaForAllocation(), + &other->path_, other->GetArenaForAllocation() + ); +} + +::PROTOBUF_NAMESPACE_ID::Metadata ProvidePeripheralFileRequest::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, + file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[0]); +} + +// =================================================================== + +class ProvidePeripheralFileResponse::_Internal { + public: + static const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& component_information_server_result(const ProvidePeripheralFileResponse* msg); +}; + +const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& +ProvidePeripheralFileResponse::_Internal::component_information_server_result(const ProvidePeripheralFileResponse* msg) { + return *msg->component_information_server_result_; +} +ProvidePeripheralFileResponse::ProvidePeripheralFileResponse(::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.component_information_server.ProvidePeripheralFileResponse) +} +ProvidePeripheralFileResponse::ProvidePeripheralFileResponse(const ProvidePeripheralFileResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_component_information_server_result()) { + component_information_server_result_ = new ::mavsdk::rpc::component_information_server::ComponentInformationServerResult(*from.component_information_server_result_); + } else { + component_information_server_result_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) +} + +inline void ProvidePeripheralFileResponse::SharedCtor() { +component_information_server_result_ = nullptr; +} + +ProvidePeripheralFileResponse::~ProvidePeripheralFileResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void ProvidePeripheralFileResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete component_information_server_result_; +} + +void ProvidePeripheralFileResponse::ArenaDtor(void* object) { + ProvidePeripheralFileResponse* _this = reinterpret_cast< ProvidePeripheralFileResponse* >(object); + (void)_this; +} +void ProvidePeripheralFileResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void ProvidePeripheralFileResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void ProvidePeripheralFileResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && component_information_server_result_ != nullptr) { + delete component_information_server_result_; + } + component_information_server_result_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* ProvidePeripheralFileResponse::_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.component_information_server.ComponentInformationServerResult component_information_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_component_information_server_result(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* ProvidePeripheralFileResponse::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.component_information_server.ComponentInformationServerResult component_information_server_result = 1; + if (this->_internal_has_component_information_server_result()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::component_information_server_result(this), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) + return target; +} + +size_t ProvidePeripheralFileResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) + 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.component_information_server.ComponentInformationServerResult component_information_server_result = 1; + if (this->_internal_has_component_information_server_result()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *component_information_server_result_); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ProvidePeripheralFileResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + ProvidePeripheralFileResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ProvidePeripheralFileResponse::GetClassData() const { return &_class_data_; } + +void ProvidePeripheralFileResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void ProvidePeripheralFileResponse::MergeFrom(const ProvidePeripheralFileResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_component_information_server_result()) { + _internal_mutable_component_information_server_result()->::mavsdk::rpc::component_information_server::ComponentInformationServerResult::MergeFrom(from._internal_component_information_server_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void ProvidePeripheralFileResponse::CopyFrom(const ProvidePeripheralFileResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ProvidePeripheralFileResponse::IsInitialized() const { + return true; +} + +void ProvidePeripheralFileResponse::InternalSwap(ProvidePeripheralFileResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(component_information_server_result_, other->component_information_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata ProvidePeripheralFileResponse::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, + file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[1]); +} + +// =================================================================== + +class ComponentInformationServerResult::_Internal { + public: +}; + +ComponentInformationServerResult::ComponentInformationServerResult(::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.component_information_server.ComponentInformationServerResult) +} +ComponentInformationServerResult::ComponentInformationServerResult(const ComponentInformationServerResult& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + result_str_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_result_str().empty()) { + result_str_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_result_str(), + GetArenaForAllocation()); + } + result_ = from.result_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_information_server.ComponentInformationServerResult) +} + +inline void ComponentInformationServerResult::SharedCtor() { +result_str_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +result_ = 0; +} + +ComponentInformationServerResult::~ComponentInformationServerResult() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void ComponentInformationServerResult::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + result_str_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +} + +void ComponentInformationServerResult::ArenaDtor(void* object) { + ComponentInformationServerResult* _this = reinterpret_cast< ComponentInformationServerResult* >(object); + (void)_this; +} +void ComponentInformationServerResult::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void ComponentInformationServerResult::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void ComponentInformationServerResult::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + result_str_.ClearToEmpty(); + result_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* ComponentInformationServerResult::_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.component_information_server.ComponentInformationServerResult.Result result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 8)) { + ::PROTOBUF_NAMESPACE_ID::uint64 val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + _internal_set_result(static_cast<::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result>(val)); + } else goto handle_unusual; + continue; + // string result_str = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18)) { + auto str = _internal_mutable_result_str(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str")); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* ComponentInformationServerResult::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result result = 1; + if (this->_internal_result() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteEnumToArray( + 1, this->_internal_result(), target); + } + + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_result_str().data(), static_cast(this->_internal_result_str().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str"); + target = stream->WriteStringMaybeAliased( + 2, this->_internal_result_str(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + return target; +} + +size_t ComponentInformationServerResult::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_result_str()); + } + + // .mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result result = 1; + if (this->_internal_result() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::EnumSize(this->_internal_result()); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ComponentInformationServerResult::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + ComponentInformationServerResult::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ComponentInformationServerResult::GetClassData() const { return &_class_data_; } + +void ComponentInformationServerResult::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void ComponentInformationServerResult::MergeFrom(const ComponentInformationServerResult& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_result_str().empty()) { + _internal_set_result_str(from._internal_result_str()); + } + if (from._internal_result() != 0) { + _internal_set_result(from._internal_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void ComponentInformationServerResult::CopyFrom(const ComponentInformationServerResult& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ComponentInformationServerResult::IsInitialized() const { + return true; +} + +void ComponentInformationServerResult::InternalSwap(ComponentInformationServerResult* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &result_str_, GetArenaForAllocation(), + &other->result_str_, other->GetArenaForAllocation() + ); + swap(result_, other->result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata ComponentInformationServerResult::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_getter, &descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto_once, + file_level_metadata_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto[2]); +} + +// @@protoc_insertion_point(namespace_scope) +} // namespace component_information_server +} // namespace rpc +} // namespace mavsdk +PROTOBUF_NAMESPACE_OPEN +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* Arena::CreateMaybeMessage< ::mavsdk::rpc::component_information_server::ComponentInformationServerResult >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::component_information_server::ComponentInformationServerResult >(arena); +} +PROTOBUF_NAMESPACE_CLOSE + +// @@protoc_insertion_point(global_scope) +#include diff --git a/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.h b/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.h new file mode 100644 index 0000000000..08b41bd308 --- /dev/null +++ b/src/mavsdk_server/src/generated/component_information_server/component_information_server.pb.h @@ -0,0 +1,847 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: component_information_server/component_information_server.proto + +#ifndef GOOGLE_PROTOBUF_INCLUDED_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto +#define GOOGLE_PROTOBUF_INCLUDED_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto + +#include +#include + +#include +#if PROTOBUF_VERSION < 3017000 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3017003 < PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "mavsdk_options.pb.h" +// @@protoc_insertion_point(includes) +#include +#define PROTOBUF_INTERNAL_EXPORT_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto +PROTOBUF_NAMESPACE_OPEN +namespace internal { +class AnyMetadata; +} // namespace internal +PROTOBUF_NAMESPACE_CLOSE + +// Internal implementation detail -- do not use these members. +struct TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto { + static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTableField entries[] + PROTOBUF_SECTION_VARIABLE(protodesc_cold); + static const ::PROTOBUF_NAMESPACE_ID::internal::AuxiliaryParseTableField aux[] + PROTOBUF_SECTION_VARIABLE(protodesc_cold); + static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[3] + PROTOBUF_SECTION_VARIABLE(protodesc_cold); + static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[]; + static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[]; + static const ::PROTOBUF_NAMESPACE_ID::uint32 offsets[]; +}; +extern const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; +namespace mavsdk { +namespace rpc { +namespace component_information_server { +class ComponentInformationServerResult; +struct ComponentInformationServerResultDefaultTypeInternal; +extern ComponentInformationServerResultDefaultTypeInternal _ComponentInformationServerResult_default_instance_; +class ProvidePeripheralFileRequest; +struct ProvidePeripheralFileRequestDefaultTypeInternal; +extern ProvidePeripheralFileRequestDefaultTypeInternal _ProvidePeripheralFileRequest_default_instance_; +class ProvidePeripheralFileResponse; +struct ProvidePeripheralFileResponseDefaultTypeInternal; +extern ProvidePeripheralFileResponseDefaultTypeInternal _ProvidePeripheralFileResponse_default_instance_; +} // namespace component_information_server +} // namespace rpc +} // namespace mavsdk +PROTOBUF_NAMESPACE_OPEN +template<> ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* Arena::CreateMaybeMessage<::mavsdk::rpc::component_information_server::ComponentInformationServerResult>(Arena*); +template<> ::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::component_information_server::ProvidePeripheralFileRequest>(Arena*); +template<> ::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::component_information_server::ProvidePeripheralFileResponse>(Arena*); +PROTOBUF_NAMESPACE_CLOSE +namespace mavsdk { +namespace rpc { +namespace component_information_server { + +enum ComponentInformationServerResult_Result : int { + ComponentInformationServerResult_Result_RESULT_UNKNOWN = 0, + ComponentInformationServerResult_Result_RESULT_SUCCESS = 1, + ComponentInformationServerResult_Result_RESULT_NOT_FOUND = 2, + ComponentInformationServerResult_Result_RESULT_OPEN_FAILURE = 3, + ComponentInformationServerResult_Result_RESULT_READ_FAILURE = 4, + ComponentInformationServerResult_Result_RESULT_FAILED_JSON_PARSING = 5, + ComponentInformationServerResult_Result_RESULT_FAILED_JSON_SCHEMA = 6, + ComponentInformationServerResult_Result_ComponentInformationServerResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::PROTOBUF_NAMESPACE_ID::int32>::min(), + ComponentInformationServerResult_Result_ComponentInformationServerResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::PROTOBUF_NAMESPACE_ID::int32>::max() +}; +bool ComponentInformationServerResult_Result_IsValid(int value); +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult_Result_Result_MIN = ComponentInformationServerResult_Result_RESULT_UNKNOWN; +constexpr ComponentInformationServerResult_Result ComponentInformationServerResult_Result_Result_MAX = ComponentInformationServerResult_Result_RESULT_FAILED_JSON_SCHEMA; +constexpr int ComponentInformationServerResult_Result_Result_ARRAYSIZE = ComponentInformationServerResult_Result_Result_MAX + 1; + +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* ComponentInformationServerResult_Result_descriptor(); +template +inline const std::string& ComponentInformationServerResult_Result_Name(T enum_t_value) { + static_assert(::std::is_same::value || + ::std::is_integral::value, + "Incorrect type passed to function ComponentInformationServerResult_Result_Name."); + return ::PROTOBUF_NAMESPACE_ID::internal::NameOfEnum( + ComponentInformationServerResult_Result_descriptor(), enum_t_value); +} +inline bool ComponentInformationServerResult_Result_Parse( + ::PROTOBUF_NAMESPACE_ID::ConstStringParam name, ComponentInformationServerResult_Result* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + ComponentInformationServerResult_Result_descriptor(), name, value); +} +// =================================================================== + +class ProvidePeripheralFileRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) */ { + public: + inline ProvidePeripheralFileRequest() : ProvidePeripheralFileRequest(nullptr) {} + ~ProvidePeripheralFileRequest() override; + explicit constexpr ProvidePeripheralFileRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + ProvidePeripheralFileRequest(const ProvidePeripheralFileRequest& from); + ProvidePeripheralFileRequest(ProvidePeripheralFileRequest&& from) noexcept + : ProvidePeripheralFileRequest() { + *this = ::std::move(from); + } + + inline ProvidePeripheralFileRequest& operator=(const ProvidePeripheralFileRequest& from) { + CopyFrom(from); + return *this; + } + inline ProvidePeripheralFileRequest& operator=(ProvidePeripheralFileRequest&& 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 ProvidePeripheralFileRequest& default_instance() { + return *internal_default_instance(); + } + static inline const ProvidePeripheralFileRequest* internal_default_instance() { + return reinterpret_cast( + &_ProvidePeripheralFileRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + friend void swap(ProvidePeripheralFileRequest& a, ProvidePeripheralFileRequest& b) { + a.Swap(&b); + } + inline void Swap(ProvidePeripheralFileRequest* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ProvidePeripheralFileRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline ProvidePeripheralFileRequest* New() const final { + return new ProvidePeripheralFileRequest(); + } + + ProvidePeripheralFileRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const ProvidePeripheralFileRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const ProvidePeripheralFileRequest& 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(ProvidePeripheralFileRequest* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest"; + } + protected: + explicit ProvidePeripheralFileRequest(::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 = 1, + }; + // string path = 1; + 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: + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr path_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class ProvidePeripheralFileResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) */ { + public: + inline ProvidePeripheralFileResponse() : ProvidePeripheralFileResponse(nullptr) {} + ~ProvidePeripheralFileResponse() override; + explicit constexpr ProvidePeripheralFileResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + ProvidePeripheralFileResponse(const ProvidePeripheralFileResponse& from); + ProvidePeripheralFileResponse(ProvidePeripheralFileResponse&& from) noexcept + : ProvidePeripheralFileResponse() { + *this = ::std::move(from); + } + + inline ProvidePeripheralFileResponse& operator=(const ProvidePeripheralFileResponse& from) { + CopyFrom(from); + return *this; + } + inline ProvidePeripheralFileResponse& operator=(ProvidePeripheralFileResponse&& 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 ProvidePeripheralFileResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ProvidePeripheralFileResponse* internal_default_instance() { + return reinterpret_cast( + &_ProvidePeripheralFileResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + friend void swap(ProvidePeripheralFileResponse& a, ProvidePeripheralFileResponse& b) { + a.Swap(&b); + } + inline void Swap(ProvidePeripheralFileResponse* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ProvidePeripheralFileResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline ProvidePeripheralFileResponse* New() const final { + return new ProvidePeripheralFileResponse(); + } + + ProvidePeripheralFileResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const ProvidePeripheralFileResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const ProvidePeripheralFileResponse& 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(ProvidePeripheralFileResponse* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse"; + } + protected: + explicit ProvidePeripheralFileResponse(::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 { + kComponentInformationServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.component_information_server.ComponentInformationServerResult component_information_server_result = 1; + bool has_component_information_server_result() const; + private: + bool _internal_has_component_information_server_result() const; + public: + void clear_component_information_server_result(); + const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& component_information_server_result() const; + PROTOBUF_MUST_USE_RESULT ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* release_component_information_server_result(); + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* mutable_component_information_server_result(); + void set_allocated_component_information_server_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult* component_information_server_result); + private: + const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& _internal_component_information_server_result() const; + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* _internal_mutable_component_information_server_result(); + public: + void unsafe_arena_set_allocated_component_information_server_result( + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* component_information_server_result); + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* unsafe_arena_release_component_information_server_result(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* component_information_server_result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class ComponentInformationServerResult final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.component_information_server.ComponentInformationServerResult) */ { + public: + inline ComponentInformationServerResult() : ComponentInformationServerResult(nullptr) {} + ~ComponentInformationServerResult() override; + explicit constexpr ComponentInformationServerResult(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + ComponentInformationServerResult(const ComponentInformationServerResult& from); + ComponentInformationServerResult(ComponentInformationServerResult&& from) noexcept + : ComponentInformationServerResult() { + *this = ::std::move(from); + } + + inline ComponentInformationServerResult& operator=(const ComponentInformationServerResult& from) { + CopyFrom(from); + return *this; + } + inline ComponentInformationServerResult& operator=(ComponentInformationServerResult&& from) noexcept { + if (this == &from) return *this; + if (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 ComponentInformationServerResult& default_instance() { + return *internal_default_instance(); + } + static inline const ComponentInformationServerResult* internal_default_instance() { + return reinterpret_cast( + &_ComponentInformationServerResult_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(ComponentInformationServerResult& a, ComponentInformationServerResult& b) { + a.Swap(&b); + } + inline void Swap(ComponentInformationServerResult* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ComponentInformationServerResult* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline ComponentInformationServerResult* New() const final { + return new ComponentInformationServerResult(); + } + + ComponentInformationServerResult* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const ComponentInformationServerResult& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const ComponentInformationServerResult& 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(ComponentInformationServerResult* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.component_information_server.ComponentInformationServerResult"; + } + protected: + explicit ComponentInformationServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef ComponentInformationServerResult_Result Result; + static constexpr Result RESULT_UNKNOWN = + ComponentInformationServerResult_Result_RESULT_UNKNOWN; + static constexpr Result RESULT_SUCCESS = + ComponentInformationServerResult_Result_RESULT_SUCCESS; + static constexpr Result RESULT_NOT_FOUND = + ComponentInformationServerResult_Result_RESULT_NOT_FOUND; + static constexpr Result RESULT_OPEN_FAILURE = + ComponentInformationServerResult_Result_RESULT_OPEN_FAILURE; + static constexpr Result RESULT_READ_FAILURE = + ComponentInformationServerResult_Result_RESULT_READ_FAILURE; + static constexpr Result RESULT_FAILED_JSON_PARSING = + ComponentInformationServerResult_Result_RESULT_FAILED_JSON_PARSING; + static constexpr Result RESULT_FAILED_JSON_SCHEMA = + ComponentInformationServerResult_Result_RESULT_FAILED_JSON_SCHEMA; + static inline bool Result_IsValid(int value) { + return ComponentInformationServerResult_Result_IsValid(value); + } + static constexpr Result Result_MIN = + ComponentInformationServerResult_Result_Result_MIN; + static constexpr Result Result_MAX = + ComponentInformationServerResult_Result_Result_MAX; + static constexpr int Result_ARRAYSIZE = + ComponentInformationServerResult_Result_Result_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* + Result_descriptor() { + return ComponentInformationServerResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T enum_t_value) { + static_assert(::std::is_same::value || + ::std::is_integral::value, + "Incorrect type passed to function Result_Name."); + return ComponentInformationServerResult_Result_Name(enum_t_value); + } + static inline bool Result_Parse(::PROTOBUF_NAMESPACE_ID::ConstStringParam name, + Result* value) { + return ComponentInformationServerResult_Result_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + enum : int { + kResultStrFieldNumber = 2, + kResultFieldNumber = 1, + }; + // string result_str = 2; + void clear_result_str(); + const std::string& result_str() const; + template + void set_result_str(ArgT0&& arg0, ArgT... args); + std::string* mutable_result_str(); + PROTOBUF_MUST_USE_RESULT std::string* release_result_str(); + void set_allocated_result_str(std::string* result_str); + private: + const std::string& _internal_result_str() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_result_str(const std::string& value); + std::string* _internal_mutable_result_str(); + public: + + // .mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result result = 1; + void clear_result(); + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result result() const; + void set_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result value); + private: + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result _internal_result() const; + void _internal_set_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result value); + public: + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr result_str_; + int result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ProvidePeripheralFileRequest + +// string path = 1; +inline void ProvidePeripheralFileRequest::clear_path() { + path_.ClearToEmpty(); +} +inline const std::string& ProvidePeripheralFileRequest::path() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest.path) + return _internal_path(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void ProvidePeripheralFileRequest::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.component_information_server.ProvidePeripheralFileRequest.path) +} +inline std::string* ProvidePeripheralFileRequest::mutable_path() { + std::string* _s = _internal_mutable_path(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest.path) + return _s; +} +inline const std::string& ProvidePeripheralFileRequest::_internal_path() const { + return path_.Get(); +} +inline void ProvidePeripheralFileRequest::_internal_set_path(const std::string& value) { + + path_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* ProvidePeripheralFileRequest::_internal_mutable_path() { + + return path_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* ProvidePeripheralFileRequest::release_path() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.ProvidePeripheralFileRequest.path) + return path_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void ProvidePeripheralFileRequest::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.component_information_server.ProvidePeripheralFileRequest.path) +} + +// ------------------------------------------------------------------- + +// ProvidePeripheralFileResponse + +// .mavsdk.rpc.component_information_server.ComponentInformationServerResult component_information_server_result = 1; +inline bool ProvidePeripheralFileResponse::_internal_has_component_information_server_result() const { + return this != internal_default_instance() && component_information_server_result_ != nullptr; +} +inline bool ProvidePeripheralFileResponse::has_component_information_server_result() const { + return _internal_has_component_information_server_result(); +} +inline void ProvidePeripheralFileResponse::clear_component_information_server_result() { + if (GetArenaForAllocation() == nullptr && component_information_server_result_ != nullptr) { + delete component_information_server_result_; + } + component_information_server_result_ = nullptr; +} +inline const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& ProvidePeripheralFileResponse::_internal_component_information_server_result() const { + const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* p = component_information_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::component_information_server::_ComponentInformationServerResult_default_instance_); +} +inline const ::mavsdk::rpc::component_information_server::ComponentInformationServerResult& ProvidePeripheralFileResponse::component_information_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse.component_information_server_result) + return _internal_component_information_server_result(); +} +inline void ProvidePeripheralFileResponse::unsafe_arena_set_allocated_component_information_server_result( + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* component_information_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(component_information_server_result_); + } + component_information_server_result_ = component_information_server_result; + if (component_information_server_result) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse.component_information_server_result) +} +inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* ProvidePeripheralFileResponse::release_component_information_server_result() { + + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* temp = component_information_server_result_; + component_information_server_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* ProvidePeripheralFileResponse::unsafe_arena_release_component_information_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse.component_information_server_result) + + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* temp = component_information_server_result_; + component_information_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* ProvidePeripheralFileResponse::_internal_mutable_component_information_server_result() { + + if (component_information_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::component_information_server::ComponentInformationServerResult>(GetArenaForAllocation()); + component_information_server_result_ = p; + } + return component_information_server_result_; +} +inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* ProvidePeripheralFileResponse::mutable_component_information_server_result() { + ::mavsdk::rpc::component_information_server::ComponentInformationServerResult* _msg = _internal_mutable_component_information_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse.component_information_server_result) + return _msg; +} +inline void ProvidePeripheralFileResponse::set_allocated_component_information_server_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult* component_information_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete component_information_server_result_; + } + if (component_information_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::component_information_server::ComponentInformationServerResult>::GetOwningArena(component_information_server_result); + if (message_arena != submessage_arena) { + component_information_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, component_information_server_result, submessage_arena); + } + + } else { + + } + component_information_server_result_ = component_information_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information_server.ProvidePeripheralFileResponse.component_information_server_result) +} + +// ------------------------------------------------------------------- + +// ComponentInformationServerResult + +// .mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result result = 1; +inline void ComponentInformationServerResult::clear_result() { + result_ = 0; +} +inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result ComponentInformationServerResult::_internal_result() const { + return static_cast< ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result >(result_); +} +inline ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result ComponentInformationServerResult::result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result) + return _internal_result(); +} +inline void ComponentInformationServerResult::_internal_set_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result value) { + + result_ = value; +} +inline void ComponentInformationServerResult::set_result(::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result value) { + _internal_set_result(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result) +} + +// string result_str = 2; +inline void ComponentInformationServerResult::clear_result_str() { + result_str_.ClearToEmpty(); +} +inline const std::string& ComponentInformationServerResult::result_str() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str) + return _internal_result_str(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void ComponentInformationServerResult::set_result_str(ArgT0&& arg0, ArgT... args) { + + result_str_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str) +} +inline std::string* ComponentInformationServerResult::mutable_result_str() { + std::string* _s = _internal_mutable_result_str(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str) + return _s; +} +inline const std::string& ComponentInformationServerResult::_internal_result_str() const { + return result_str_.Get(); +} +inline void ComponentInformationServerResult::_internal_set_result_str(const std::string& value) { + + result_str_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* ComponentInformationServerResult::_internal_mutable_result_str() { + + return result_str_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* ComponentInformationServerResult::release_result_str() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str) + return result_str_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void ComponentInformationServerResult::set_allocated_result_str(std::string* result_str) { + if (result_str != nullptr) { + + } else { + + } + result_str_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), result_str, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.component_information_server.ComponentInformationServerResult.result_str) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace component_information_server +} // namespace rpc +} // namespace mavsdk + +PROTOBUF_NAMESPACE_OPEN + +template <> struct is_proto_enum< ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result>() { + return ::mavsdk::rpc::component_information_server::ComponentInformationServerResult_Result_descriptor(); +} + +PROTOBUF_NAMESPACE_CLOSE + +// @@protoc_insertion_point(global_scope) + +#include +#endif // GOOGLE_PROTOBUF_INCLUDED_GOOGLE_PROTOBUF_INCLUDED_component_5finformation_5fserver_2fcomponent_5finformation_5fserver_2eproto diff --git a/src/mavsdk_server/src/plugins/component_information_server/component_information_server_service_impl.h b/src/mavsdk_server/src/plugins/component_information_server/component_information_server_service_impl.h new file mode 100644 index 0000000000..eb3830e889 --- /dev/null +++ b/src/mavsdk_server/src/plugins/component_information_server/component_information_server_service_impl.h @@ -0,0 +1,179 @@ +// WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. +// Edits need to be made to the proto files +// (see +// https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/component_information_server/component_information_server.proto) + +#include "component_information_server/component_information_server.grpc.pb.h" +#include "plugins/component_information_server/component_information_server.h" + +#include "mavsdk.h" +#include "lazy_plugin.h" +#include "log.h" +#include +#include +#include +#include +#include +#include +#include + +namespace mavsdk { +namespace mavsdk_server { + +template< + typename ComponentInformationServer = ComponentInformationServer, + typename LazyPlugin = LazyPlugin> +class ComponentInformationServerServiceImpl final + : public rpc::component_information_server::ComponentInformationServerService::Service { +public: + ComponentInformationServerServiceImpl(LazyPlugin& lazy_plugin) : _lazy_plugin(lazy_plugin) {} + + template + void fillResponseWithResult( + ResponseType* response, mavsdk::ComponentInformationServer::Result& result) const + { + auto rpc_result = translateToRpcResult(result); + + auto* rpc_component_information_server_result = + new rpc::component_information_server::ComponentInformationServerResult(); + rpc_component_information_server_result->set_result(rpc_result); + std::stringstream ss; + ss << result; + rpc_component_information_server_result->set_result_str(ss.str()); + + response->set_allocated_component_information_server_result( + rpc_component_information_server_result); + } + + static rpc::component_information_server::ComponentInformationServerResult::Result + translateToRpcResult(const mavsdk::ComponentInformationServer::Result& result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case mavsdk::ComponentInformationServer::Result::Unknown: + return rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_UNKNOWN; + case mavsdk::ComponentInformationServer::Result::Success: + return rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_SUCCESS; + case mavsdk::ComponentInformationServer::Result::NotFound: + return rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_NOT_FOUND; + case mavsdk::ComponentInformationServer::Result::OpenFailure: + return rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_OPEN_FAILURE; + case mavsdk::ComponentInformationServer::Result::ReadFailure: + return rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_READ_FAILURE; + case mavsdk::ComponentInformationServer::Result::FailedJsonParsing: + return rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_FAILED_JSON_PARSING; + case mavsdk::ComponentInformationServer::Result::FailedJsonSchema: + return rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_FAILED_JSON_SCHEMA; + } + } + + static mavsdk::ComponentInformationServer::Result translateFromRpcResult( + const rpc::component_information_server::ComponentInformationServerResult::Result result) + { + switch (result) { + default: + LogErr() << "Unknown result enum value: " << static_cast(result); + // FALLTHROUGH + case rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_UNKNOWN: + return mavsdk::ComponentInformationServer::Result::Unknown; + case rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_SUCCESS: + return mavsdk::ComponentInformationServer::Result::Success; + case rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_NOT_FOUND: + return mavsdk::ComponentInformationServer::Result::NotFound; + case rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_OPEN_FAILURE: + return mavsdk::ComponentInformationServer::Result::OpenFailure; + case rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_READ_FAILURE: + return mavsdk::ComponentInformationServer::Result::ReadFailure; + case rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_FAILED_JSON_PARSING: + return mavsdk::ComponentInformationServer::Result::FailedJsonParsing; + case rpc::component_information_server:: + ComponentInformationServerResult_Result_RESULT_FAILED_JSON_SCHEMA: + return mavsdk::ComponentInformationServer::Result::FailedJsonSchema; + } + } + + grpc::Status ProvidePeripheralFile( + grpc::ServerContext* /* context */, + const rpc::component_information_server::ProvidePeripheralFileRequest* request, + rpc::component_information_server::ProvidePeripheralFileResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::ComponentInformationServer::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "ProvidePeripheralFile sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->provide_peripheral_file(request->path()); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + void stop() + { + _stopped.store(true); + for (auto& prom : _stream_stop_promises) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } + } + +private: + void register_stream_stop_promise(std::weak_ptr> prom) + { + // If we have already stopped, set promise immediately and don't add it to list. + if (_stopped.load()) { + if (auto handle = prom.lock()) { + handle->set_value(); + } + } else { + _stream_stop_promises.push_back(prom); + } + } + + void unregister_stream_stop_promise(std::shared_ptr> prom) + { + for (auto it = _stream_stop_promises.begin(); it != _stream_stop_promises.end(); + /* ++it */) { + if (it->lock() == prom) { + it = _stream_stop_promises.erase(it); + } else { + ++it; + } + } + } + + LazyPlugin& _lazy_plugin; + std::atomic _stopped{false}; + std::vector>> _stream_stop_promises{}; +}; + +} // namespace mavsdk_server +} // namespace mavsdk \ No newline at end of file