diff --git a/proto b/proto index 34bce6d61d..9e7b3d42c3 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 34bce6d61dba5f72b602bdbd31f04fceff093881 +Subproject commit 9e7b3d42c394e0bc38dfd83d22c90b7f15763bd5 diff --git a/src/mavsdk_server/src/core/core_service_impl.h b/src/mavsdk_server/src/core/core_service_impl.h index 876ea9744e..8e3278bd38 100644 --- a/src/mavsdk_server/src/core/core_service_impl.h +++ b/src/mavsdk_server/src/core/core_service_impl.h @@ -43,6 +43,27 @@ class CoreServiceImpl final : public mavsdk::rpc::core::CoreService::Service { return grpc::Status::OK; } + grpc::Status ListComponents( + grpc::ServerContext* /* context */, + const rpc::core::ListComponentsRequest* /* request */, + rpc::core::ListComponentsResponse* response) override + { + auto systems = _mavsdk.systems(); + for (const auto& system : systems) { + // Create a new SystemComponents message for each system. + auto* system_components = response->add_systems(); + + // Set the system_id for the current system. + system_components->set_system_id(system->get_system_id()); + + // Iterate over component IDs and add them to the current system's component list. + for (const auto& component_id : system->component_ids()) { + system_components->add_component_ids(component_id); + } + } + return grpc::Status::OK; + } + void stop() { _stop_promise.set_value(); } private: diff --git a/src/mavsdk_server/src/generated/core/core.grpc.pb.cc b/src/mavsdk_server/src/generated/core/core.grpc.pb.cc index ac4bd3fdb6..adde748071 100644 --- a/src/mavsdk_server/src/generated/core/core.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/core/core.grpc.pb.cc @@ -26,6 +26,7 @@ namespace core { static const char* CoreService_method_names[] = { "/mavsdk.rpc.core.CoreService/SubscribeConnectionState", "/mavsdk.rpc.core.CoreService/SetMavlinkTimeout", + "/mavsdk.rpc.core.CoreService/ListComponents", }; std::unique_ptr< CoreService::Stub> CoreService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -37,6 +38,7 @@ std::unique_ptr< CoreService::Stub> CoreService::NewStub(const std::shared_ptr< CoreService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) : channel_(channel), rpcmethod_SubscribeConnectionState_(CoreService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SetMavlinkTimeout_(CoreService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ListComponents_(CoreService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::ClientReader< ::mavsdk::rpc::core::ConnectionStateResponse>* CoreService::Stub::SubscribeConnectionStateRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SubscribeConnectionStateRequest& request) { @@ -78,6 +80,29 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::SetMavlinkTimeoutRespons return result; } +::grpc::Status CoreService::Stub::ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::mavsdk::rpc::core::ListComponentsResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::core::ListComponentsRequest, ::mavsdk::rpc::core::ListComponentsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_ListComponents_, context, request, response); +} + +void CoreService::Stub::async::ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::core::ListComponentsRequest, ::mavsdk::rpc::core::ListComponentsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ListComponents_, context, request, response, std::move(f)); +} + +void CoreService::Stub::async::ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ListComponents_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::ListComponentsResponse>* CoreService::Stub::PrepareAsyncListComponentsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::core::ListComponentsResponse, ::mavsdk::rpc::core::ListComponentsRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_ListComponents_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::ListComponentsResponse>* CoreService::Stub::AsyncListComponentsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncListComponentsRaw(context, request, cq); + result->StartCall(); + return result; +} + CoreService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CoreService_method_names[0], @@ -99,6 +124,16 @@ CoreService::Service::Service() { ::mavsdk::rpc::core::SetMavlinkTimeoutResponse* resp) { return service->SetMavlinkTimeout(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CoreService_method_names[2], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CoreService::Service, ::mavsdk::rpc::core::ListComponentsRequest, ::mavsdk::rpc::core::ListComponentsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CoreService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::core::ListComponentsRequest* req, + ::mavsdk::rpc::core::ListComponentsResponse* resp) { + return service->ListComponents(ctx, req, resp); + }, this))); } CoreService::Service::~Service() { @@ -118,6 +153,13 @@ ::grpc::Status CoreService::Service::SetMavlinkTimeout(::grpc::ServerContext* co return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CoreService::Service::ListComponents(::grpc::ServerContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/core/core.grpc.pb.h b/src/mavsdk_server/src/generated/core/core.grpc.pb.h index 97e73ce357..b017b3f37b 100644 --- a/src/mavsdk_server/src/generated/core/core.grpc.pb.h +++ b/src/mavsdk_server/src/generated/core/core.grpc.pb.h @@ -63,6 +63,15 @@ class CoreService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::SetMavlinkTimeoutResponse>> PrepareAsyncSetMavlinkTimeout(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::SetMavlinkTimeoutResponse>>(PrepareAsyncSetMavlinkTimeoutRaw(context, request, cq)); } + // + // List all components (computers, cameras, servos, gimbals, etc.) connected to the system. + virtual ::grpc::Status ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::mavsdk::rpc::core::ListComponentsResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::ListComponentsResponse>> AsyncListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::ListComponentsResponse>>(AsyncListComponentsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::ListComponentsResponse>> PrepareAsyncListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::ListComponentsResponse>>(PrepareAsyncListComponentsRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -78,6 +87,10 @@ class CoreService final { // need to be increased to prevent timeouts. virtual void SetMavlinkTimeout(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest* request, ::mavsdk::rpc::core::SetMavlinkTimeoutResponse* response, std::function) = 0; virtual void SetMavlinkTimeout(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest* request, ::mavsdk::rpc::core::SetMavlinkTimeoutResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // List all components (computers, cameras, servos, gimbals, etc.) connected to the system. + virtual void ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response, std::function) = 0; + virtual void ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -88,6 +101,8 @@ class CoreService final { virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::core::ConnectionStateResponse>* PrepareAsyncSubscribeConnectionStateRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SubscribeConnectionStateRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::SetMavlinkTimeoutResponse>* AsyncSetMavlinkTimeoutRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::SetMavlinkTimeoutResponse>* PrepareAsyncSetMavlinkTimeoutRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::ListComponentsResponse>* AsyncListComponentsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::core::ListComponentsResponse>* PrepareAsyncListComponentsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -108,12 +123,21 @@ class CoreService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::SetMavlinkTimeoutResponse>> PrepareAsyncSetMavlinkTimeout(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::SetMavlinkTimeoutResponse>>(PrepareAsyncSetMavlinkTimeoutRaw(context, request, cq)); } + ::grpc::Status ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::mavsdk::rpc::core::ListComponentsResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::ListComponentsResponse>> AsyncListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::ListComponentsResponse>>(AsyncListComponentsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::ListComponentsResponse>> PrepareAsyncListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::ListComponentsResponse>>(PrepareAsyncListComponentsRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: void SubscribeConnectionState(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SubscribeConnectionStateRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::core::ConnectionStateResponse>* reactor) override; void SetMavlinkTimeout(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest* request, ::mavsdk::rpc::core::SetMavlinkTimeoutResponse* response, std::function) override; void SetMavlinkTimeout(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest* request, ::mavsdk::rpc::core::SetMavlinkTimeoutResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response, std::function) override; + void ListComponents(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -130,8 +154,11 @@ class CoreService final { ::grpc::ClientAsyncReader< ::mavsdk::rpc::core::ConnectionStateResponse>* PrepareAsyncSubscribeConnectionStateRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SubscribeConnectionStateRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::SetMavlinkTimeoutResponse>* AsyncSetMavlinkTimeoutRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::SetMavlinkTimeoutResponse>* PrepareAsyncSetMavlinkTimeoutRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::ListComponentsResponse>* AsyncListComponentsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::core::ListComponentsResponse>* PrepareAsyncListComponentsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::core::ListComponentsRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SubscribeConnectionState_; const ::grpc::internal::RpcMethod rpcmethod_SetMavlinkTimeout_; + const ::grpc::internal::RpcMethod rpcmethod_ListComponents_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -150,6 +177,9 @@ class CoreService final { // if MAVSDK has to communicate over links with high latency it might // need to be increased to prevent timeouts. virtual ::grpc::Status SetMavlinkTimeout(::grpc::ServerContext* context, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest* request, ::mavsdk::rpc::core::SetMavlinkTimeoutResponse* response); + // + // List all components (computers, cameras, servos, gimbals, etc.) connected to the system. + virtual ::grpc::Status ListComponents(::grpc::ServerContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response); }; template class WithAsyncMethod_SubscribeConnectionState : public BaseClass { @@ -191,7 +221,27 @@ class CoreService final { ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SubscribeConnectionState > AsyncService; + template + class WithAsyncMethod_ListComponents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_ListComponents() { + ::grpc::Service::MarkMethodAsync(2); + } + ~WithAsyncMethod_ListComponents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ListComponents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::core::ListComponentsRequest* /*request*/, ::mavsdk::rpc::core::ListComponentsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestListComponents(::grpc::ServerContext* context, ::mavsdk::rpc::core::ListComponentsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::core::ListComponentsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SubscribeConnectionState > > AsyncService; template class WithCallbackMethod_SubscribeConnectionState : public BaseClass { private: @@ -241,7 +291,34 @@ class CoreService final { virtual ::grpc::ServerUnaryReactor* SetMavlinkTimeout( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::core::SetMavlinkTimeoutRequest* /*request*/, ::mavsdk::rpc::core::SetMavlinkTimeoutResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_SubscribeConnectionState > CallbackService; + template + class WithCallbackMethod_ListComponents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_ListComponents() { + ::grpc::Service::MarkMethodCallback(2, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::core::ListComponentsRequest, ::mavsdk::rpc::core::ListComponentsResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::core::ListComponentsRequest* request, ::mavsdk::rpc::core::ListComponentsResponse* response) { return this->ListComponents(context, request, response); }));} + void SetMessageAllocatorFor_ListComponents( + ::grpc::MessageAllocator< ::mavsdk::rpc::core::ListComponentsRequest, ::mavsdk::rpc::core::ListComponentsResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::core::ListComponentsRequest, ::mavsdk::rpc::core::ListComponentsResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_ListComponents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ListComponents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::core::ListComponentsRequest* /*request*/, ::mavsdk::rpc::core::ListComponentsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ListComponents( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::core::ListComponentsRequest* /*request*/, ::mavsdk::rpc::core::ListComponentsResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SubscribeConnectionState > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SubscribeConnectionState : public BaseClass { @@ -278,6 +355,23 @@ class CoreService final { } }; template + class WithGenericMethod_ListComponents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_ListComponents() { + ::grpc::Service::MarkMethodGeneric(2); + } + ~WithGenericMethod_ListComponents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ListComponents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::core::ListComponentsRequest* /*request*/, ::mavsdk::rpc::core::ListComponentsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SubscribeConnectionState : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -318,6 +412,26 @@ class CoreService final { } }; template + class WithRawMethod_ListComponents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ListComponents() { + ::grpc::Service::MarkMethodRaw(2); + } + ~WithRawMethod_ListComponents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ListComponents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::core::ListComponentsRequest* /*request*/, ::mavsdk::rpc::core::ListComponentsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestListComponents(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_SubscribeConnectionState : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -362,6 +476,28 @@ class CoreService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_ListComponents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_ListComponents() { + ::grpc::Service::MarkMethodRawCallback(2, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ListComponents(context, request, response); })); + } + ~WithRawCallbackMethod_ListComponents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ListComponents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::core::ListComponentsRequest* /*request*/, ::mavsdk::rpc::core::ListComponentsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ListComponents( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetMavlinkTimeout : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -388,7 +524,34 @@ class CoreService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedSetMavlinkTimeout(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::core::SetMavlinkTimeoutRequest,::mavsdk::rpc::core::SetMavlinkTimeoutResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_SetMavlinkTimeout StreamedUnaryService; + template + class WithStreamedUnaryMethod_ListComponents : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_ListComponents() { + ::grpc::Service::MarkMethodStreamed(2, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::core::ListComponentsRequest, ::mavsdk::rpc::core::ListComponentsResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::core::ListComponentsRequest, ::mavsdk::rpc::core::ListComponentsResponse>* streamer) { + return this->StreamedListComponents(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_ListComponents() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status ListComponents(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::core::ListComponentsRequest* /*request*/, ::mavsdk::rpc::core::ListComponentsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedListComponents(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::core::ListComponentsRequest,::mavsdk::rpc::core::ListComponentsResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_SetMavlinkTimeout > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeConnectionState : public BaseClass { private: @@ -417,7 +580,7 @@ class CoreService final { virtual ::grpc::Status StreamedSubscribeConnectionState(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::core::SubscribeConnectionStateRequest,::mavsdk::rpc::core::ConnectionStateResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeConnectionState SplitStreamedService; - typedef WithSplitStreamingMethod_SubscribeConnectionState > StreamedService; + typedef WithSplitStreamingMethod_SubscribeConnectionState > > StreamedService; }; } // namespace core diff --git a/src/mavsdk_server/src/generated/core/core.pb.cc b/src/mavsdk_server/src/generated/core/core.pb.cc index 743d686736..37ec61a7b3 100644 --- a/src/mavsdk_server/src/generated/core/core.pb.cc +++ b/src/mavsdk_server/src/generated/core/core.pb.cc @@ -23,6 +23,27 @@ namespace _fl = ::google::protobuf::internal::field_layout; namespace mavsdk { namespace rpc { namespace core { + +inline constexpr SystemComponents::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : component_ids_{}, + _component_ids_cached_byte_size_{0}, + system_id_{0u}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR SystemComponents::SystemComponents(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct SystemComponentsDefaultTypeInternal { + PROTOBUF_CONSTEXPR SystemComponentsDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SystemComponentsDefaultTypeInternal() {} + union { + SystemComponents _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SystemComponentsDefaultTypeInternal _SystemComponents_default_instance_; template PROTOBUF_CONSTEXPR SubscribeConnectionStateRequest::SubscribeConnectionStateRequest(::_pbi::ConstantInitialized) {} struct SubscribeConnectionStateRequestDefaultTypeInternal { @@ -66,6 +87,18 @@ struct SetMavlinkTimeoutRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetMavlinkTimeoutRequestDefaultTypeInternal _SetMavlinkTimeoutRequest_default_instance_; + template +PROTOBUF_CONSTEXPR ListComponentsRequest::ListComponentsRequest(::_pbi::ConstantInitialized) {} +struct ListComponentsRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR ListComponentsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ListComponentsRequestDefaultTypeInternal() {} + union { + ListComponentsRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ListComponentsRequestDefaultTypeInternal _ListComponentsRequest_default_instance_; inline constexpr ConnectionState::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept @@ -86,6 +119,25 @@ struct ConnectionStateDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ConnectionStateDefaultTypeInternal _ConnectionState_default_instance_; +inline constexpr ListComponentsResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : systems_{}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ListComponentsResponse::ListComponentsResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ListComponentsResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ListComponentsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ListComponentsResponseDefaultTypeInternal() {} + union { + ListComponentsResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ListComponentsResponseDefaultTypeInternal _ListComponentsResponse_default_instance_; + inline constexpr ConnectionStateResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -107,7 +159,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace core } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_core_2fcore_2eproto[5]; +static ::_pb::Metadata file_level_metadata_core_2fcore_2eproto[8]; static constexpr const ::_pb::EnumDescriptor** file_level_enum_descriptors_core_2fcore_2eproto = nullptr; static constexpr const ::_pb::ServiceDescriptor** @@ -158,6 +210,33 @@ const ::uint32_t TableStruct_core_2fcore_2eproto::offsets[] PROTOBUF_SECTION_VAR ~0u, // no _split_ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::core::ConnectionState, _impl_.is_connected_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::core::ListComponentsRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::core::SystemComponents, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::core::SystemComponents, _impl_.system_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::core::SystemComponents, _impl_.component_ids_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::core::ListComponentsResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::core::ListComponentsResponse, _impl_.systems_), }; static const ::_pbi::MigrationSchema @@ -167,6 +246,9 @@ static const ::_pbi::MigrationSchema {18, -1, -1, sizeof(::mavsdk::rpc::core::SetMavlinkTimeoutRequest)}, {27, -1, -1, sizeof(::mavsdk::rpc::core::SetMavlinkTimeoutResponse)}, {35, -1, -1, sizeof(::mavsdk::rpc::core::ConnectionState)}, + {44, -1, -1, sizeof(::mavsdk::rpc::core::ListComponentsRequest)}, + {52, -1, -1, sizeof(::mavsdk::rpc::core::SystemComponents)}, + {62, -1, -1, sizeof(::mavsdk::rpc::core::ListComponentsResponse)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -175,6 +257,9 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::core::_SetMavlinkTimeoutRequest_default_instance_._instance, &::mavsdk::rpc::core::_SetMavlinkTimeoutResponse_default_instance_._instance, &::mavsdk::rpc::core::_ConnectionState_default_instance_._instance, + &::mavsdk::rpc::core::_ListComponentsRequest_default_instance_._instance, + &::mavsdk::rpc::core::_SystemComponents_default_instance_._instance, + &::mavsdk::rpc::core::_ListComponentsResponse_default_instance_._instance, }; const char descriptor_table_protodef_core_2fcore_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { "\n\017core/core.proto\022\017mavsdk.rpc.core\"!\n\037Su" @@ -183,26 +268,33 @@ const char descriptor_table_protodef_core_2fcore_2eproto[] PROTOBUF_SECTION_VARI "(\0132 .mavsdk.rpc.core.ConnectionState\"-\n\030" "SetMavlinkTimeoutRequest\022\021\n\ttimeout_s\030\001 " "\001(\001\"\033\n\031SetMavlinkTimeoutResponse\"\'\n\017Conn" - "ectionState\022\024\n\014is_connected\030\002 \001(\0102\367\001\n\013Co" - "reService\022z\n\030SubscribeConnectionState\0220." - "mavsdk.rpc.core.SubscribeConnectionState" - "Request\032(.mavsdk.rpc.core.ConnectionStat" - "eResponse\"\0000\001\022l\n\021SetMavlinkTimeout\022).mav" - "sdk.rpc.core.SetMavlinkTimeoutRequest\032*." - "mavsdk.rpc.core.SetMavlinkTimeoutRespons" - "e\"\000B\033\n\016io.mavsdk.coreB\tCoreProtob\006proto3" + "ectionState\022\024\n\014is_connected\030\002 \001(\010\"\027\n\025Lis" + "tComponentsRequest\"<\n\020SystemComponents\022\021" + "\n\tsystem_id\030\001 \001(\r\022\025\n\rcomponent_ids\030\002 \003(\r" + "\"L\n\026ListComponentsResponse\0222\n\007systems\030\001 " + "\003(\0132!.mavsdk.rpc.core.SystemComponents2\334" + "\002\n\013CoreService\022z\n\030SubscribeConnectionSta" + "te\0220.mavsdk.rpc.core.SubscribeConnection" + "StateRequest\032(.mavsdk.rpc.core.Connectio" + "nStateResponse\"\0000\001\022l\n\021SetMavlinkTimeout\022" + ").mavsdk.rpc.core.SetMavlinkTimeoutReque" + "st\032*.mavsdk.rpc.core.SetMavlinkTimeoutRe" + "sponse\"\000\022c\n\016ListComponents\022&.mavsdk.rpc." + "core.ListComponentsRequest\032\'.mavsdk.rpc." + "core.ListComponentsResponse\"\000B\033\n\016io.mavs" + "dk.coreB\tCoreProtob\006proto3" }; static ::absl::once_flag descriptor_table_core_2fcore_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_core_2fcore_2eproto = { false, false, - 560, + 826, descriptor_table_protodef_core_2fcore_2eproto, "core/core.proto", &descriptor_table_core_2fcore_2eproto_once, nullptr, 0, - 5, + 8, schemas, file_default_instances, TableStruct_core_2fcore_2eproto::offsets, @@ -861,6 +953,442 @@ ::google::protobuf::Metadata ConnectionState::GetMetadata() const { &descriptor_table_core_2fcore_2eproto_getter, &descriptor_table_core_2fcore_2eproto_once, file_level_metadata_core_2fcore_2eproto[4]); } +// =================================================================== + +class ListComponentsRequest::_Internal { + public: +}; + +ListComponentsRequest::ListComponentsRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.core.ListComponentsRequest) +} +ListComponentsRequest::ListComponentsRequest( + ::google::protobuf::Arena* arena, + const ListComponentsRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + ListComponentsRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.core.ListComponentsRequest) +} + + + + + + + + + +::google::protobuf::Metadata ListComponentsRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_core_2fcore_2eproto_getter, &descriptor_table_core_2fcore_2eproto_once, + file_level_metadata_core_2fcore_2eproto[5]); +} +// =================================================================== + +class SystemComponents::_Internal { + public: +}; + +SystemComponents::SystemComponents(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.core.SystemComponents) +} +inline PROTOBUF_NDEBUG_INLINE SystemComponents::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : component_ids_{visibility, arena, from.component_ids_}, + _component_ids_cached_byte_size_{0}, + _cached_size_{0} {} + +SystemComponents::SystemComponents( + ::google::protobuf::Arena* arena, + const SystemComponents& from) + : ::google::protobuf::Message(arena) { + SystemComponents* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + _impl_.system_id_ = from._impl_.system_id_; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.core.SystemComponents) +} +inline PROTOBUF_NDEBUG_INLINE SystemComponents::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : component_ids_{visibility, arena}, + _component_ids_cached_byte_size_{0}, + _cached_size_{0} {} + +inline void SystemComponents::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.system_id_ = {}; +} +SystemComponents::~SystemComponents() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.core.SystemComponents) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void SystemComponents::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void SystemComponents::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.core.SystemComponents) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.component_ids_.Clear(); + _impl_.system_id_ = 0u; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* SystemComponents::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> SystemComponents::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 2, 8, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967292, // skipmap + offsetof(decltype(_table_), field_entries), + 2, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_SystemComponents_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // repeated uint32 component_ids = 2; + {::_pbi::TcParser::FastV32P1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(SystemComponents, _impl_.component_ids_)}}, + // uint32 system_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SystemComponents, _impl_.system_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(SystemComponents, _impl_.system_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // uint32 system_id = 1; + {PROTOBUF_FIELD_OFFSET(SystemComponents, _impl_.system_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, + // repeated uint32 component_ids = 2; + {PROTOBUF_FIELD_OFFSET(SystemComponents, _impl_.component_ids_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kPackedUInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* SystemComponents::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.core.SystemComponents) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // uint32 system_id = 1; + if (this->_internal_system_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 1, this->_internal_system_id(), target); + } + + // repeated uint32 component_ids = 2; + { + int byte_size = _impl_._component_ids_cached_byte_size_.Get(); + if (byte_size > 0) { + target = stream->WriteUInt32Packed( + 2, _internal_component_ids(), byte_size, target); + } + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.core.SystemComponents) + return target; +} + +::size_t SystemComponents::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.core.SystemComponents) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // repeated uint32 component_ids = 2; + { + std::size_t data_size = ::_pbi::WireFormatLite::UInt32Size( + this->_internal_component_ids()) + ; + _impl_._component_ids_cached_byte_size_.Set(::_pbi::ToCachedSize(data_size)); + std::size_t tag_size = data_size == 0 + ? 0 + : 1 + ::_pbi::WireFormatLite::Int32Size( + static_cast(data_size)) + ; + total_size += tag_size + data_size; + } + // uint32 system_id = 1; + if (this->_internal_system_id() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_system_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData SystemComponents::_class_data_ = { + SystemComponents::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* SystemComponents::GetClassData() const { + return &_class_data_; +} + +void SystemComponents::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.core.SystemComponents) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + _this->_internal_mutable_component_ids()->MergeFrom(from._internal_component_ids()); + if (from._internal_system_id() != 0) { + _this->_internal_set_system_id(from._internal_system_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void SystemComponents::CopyFrom(const SystemComponents& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.core.SystemComponents) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool SystemComponents::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* SystemComponents::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void SystemComponents::InternalSwap(SystemComponents* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + _impl_.component_ids_.InternalSwap(&other->_impl_.component_ids_); + swap(_impl_.system_id_, other->_impl_.system_id_); +} + +::google::protobuf::Metadata SystemComponents::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_core_2fcore_2eproto_getter, &descriptor_table_core_2fcore_2eproto_once, + file_level_metadata_core_2fcore_2eproto[6]); +} +// =================================================================== + +class ListComponentsResponse::_Internal { + public: +}; + +ListComponentsResponse::ListComponentsResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.core.ListComponentsResponse) +} +inline PROTOBUF_NDEBUG_INLINE ListComponentsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : systems_{visibility, arena, from.systems_}, + _cached_size_{0} {} + +ListComponentsResponse::ListComponentsResponse( + ::google::protobuf::Arena* arena, + const ListComponentsResponse& from) + : ::google::protobuf::Message(arena) { + ListComponentsResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.core.ListComponentsResponse) +} +inline PROTOBUF_NDEBUG_INLINE ListComponentsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : systems_{visibility, arena}, + _cached_size_{0} {} + +inline void ListComponentsResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); +} +ListComponentsResponse::~ListComponentsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.core.ListComponentsResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ListComponentsResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ListComponentsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.core.ListComponentsResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.systems_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ListComponentsResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ListComponentsResponse::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_ListComponentsResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // repeated .mavsdk.rpc.core.SystemComponents systems = 1; + {::_pbi::TcParser::FastMtR1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(ListComponentsResponse, _impl_.systems_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // repeated .mavsdk.rpc.core.SystemComponents systems = 1; + {PROTOBUF_FIELD_OFFSET(ListComponentsResponse, _impl_.systems_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::core::SystemComponents>()}, + }}, {{ + }}, +}; + +::uint8_t* ListComponentsResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.core.ListComponentsResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // repeated .mavsdk.rpc.core.SystemComponents systems = 1; + for (unsigned i = 0, + n = static_cast(this->_internal_systems_size()); i < n; i++) { + const auto& repfield = this->_internal_systems().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(1, repfield, repfield.GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.core.ListComponentsResponse) + return target; +} + +::size_t ListComponentsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.core.ListComponentsResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // repeated .mavsdk.rpc.core.SystemComponents systems = 1; + total_size += 1UL * this->_internal_systems_size(); + for (const auto& msg : this->_internal_systems()) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ListComponentsResponse::_class_data_ = { + ListComponentsResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ListComponentsResponse::GetClassData() const { + return &_class_data_; +} + +void ListComponentsResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.core.ListComponentsResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + _this->_internal_mutable_systems()->MergeFrom( + from._internal_systems()); + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ListComponentsResponse::CopyFrom(const ListComponentsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.core.ListComponentsResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ListComponentsResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ListComponentsResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ListComponentsResponse::InternalSwap(ListComponentsResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + _impl_.systems_.InternalSwap(&other->_impl_.systems_); +} + +::google::protobuf::Metadata ListComponentsResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_core_2fcore_2eproto_getter, &descriptor_table_core_2fcore_2eproto_once, + file_level_metadata_core_2fcore_2eproto[7]); +} // @@protoc_insertion_point(namespace_scope) } // namespace core } // namespace rpc diff --git a/src/mavsdk_server/src/generated/core/core.pb.h b/src/mavsdk_server/src/generated/core/core.pb.h index d1c2d657c7..aa559a4348 100644 --- a/src/mavsdk_server/src/generated/core/core.pb.h +++ b/src/mavsdk_server/src/generated/core/core.pb.h @@ -65,6 +65,12 @@ extern ConnectionStateDefaultTypeInternal _ConnectionState_default_instance_; class ConnectionStateResponse; struct ConnectionStateResponseDefaultTypeInternal; extern ConnectionStateResponseDefaultTypeInternal _ConnectionStateResponse_default_instance_; +class ListComponentsRequest; +struct ListComponentsRequestDefaultTypeInternal; +extern ListComponentsRequestDefaultTypeInternal _ListComponentsRequest_default_instance_; +class ListComponentsResponse; +struct ListComponentsResponseDefaultTypeInternal; +extern ListComponentsResponseDefaultTypeInternal _ListComponentsResponse_default_instance_; class SetMavlinkTimeoutRequest; struct SetMavlinkTimeoutRequestDefaultTypeInternal; extern SetMavlinkTimeoutRequestDefaultTypeInternal _SetMavlinkTimeoutRequest_default_instance_; @@ -74,6 +80,9 @@ extern SetMavlinkTimeoutResponseDefaultTypeInternal _SetMavlinkTimeoutResponse_d class SubscribeConnectionStateRequest; struct SubscribeConnectionStateRequestDefaultTypeInternal; extern SubscribeConnectionStateRequestDefaultTypeInternal _SubscribeConnectionStateRequest_default_instance_; +class SystemComponents; +struct SystemComponentsDefaultTypeInternal; +extern SystemComponentsDefaultTypeInternal _SystemComponents_default_instance_; } // namespace core } // namespace rpc } // namespace mavsdk @@ -91,6 +100,202 @@ namespace core { // ------------------------------------------------------------------- +class SystemComponents final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.core.SystemComponents) */ { + public: + inline SystemComponents() : SystemComponents(nullptr) {} + ~SystemComponents() override; + template + explicit PROTOBUF_CONSTEXPR SystemComponents(::google::protobuf::internal::ConstantInitialized); + + inline SystemComponents(const SystemComponents& from) + : SystemComponents(nullptr, from) {} + SystemComponents(SystemComponents&& from) noexcept + : SystemComponents() { + *this = ::std::move(from); + } + + inline SystemComponents& operator=(const SystemComponents& from) { + CopyFrom(from); + return *this; + } + inline SystemComponents& operator=(SystemComponents&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SystemComponents& default_instance() { + return *internal_default_instance(); + } + static inline const SystemComponents* internal_default_instance() { + return reinterpret_cast( + &_SystemComponents_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + friend void swap(SystemComponents& a, SystemComponents& b) { + a.Swap(&b); + } + inline void Swap(SystemComponents* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SystemComponents* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SystemComponents* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const SystemComponents& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const SystemComponents& from) { + SystemComponents::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(SystemComponents* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.core.SystemComponents"; + } + protected: + explicit SystemComponents(::google::protobuf::Arena* arena); + SystemComponents(::google::protobuf::Arena* arena, const SystemComponents& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kComponentIdsFieldNumber = 2, + kSystemIdFieldNumber = 1, + }; + // repeated uint32 component_ids = 2; + int component_ids_size() const; + private: + int _internal_component_ids_size() const; + + public: + void clear_component_ids() ; + ::uint32_t component_ids(int index) const; + void set_component_ids(int index, ::uint32_t value); + void add_component_ids(::uint32_t value); + const ::google::protobuf::RepeatedField<::uint32_t>& component_ids() const; + ::google::protobuf::RepeatedField<::uint32_t>* mutable_component_ids(); + + private: + const ::google::protobuf::RepeatedField<::uint32_t>& _internal_component_ids() const; + ::google::protobuf::RepeatedField<::uint32_t>* _internal_mutable_component_ids(); + + public: + // uint32 system_id = 1; + void clear_system_id() ; + ::uint32_t system_id() const; + void set_system_id(::uint32_t value); + + private: + ::uint32_t _internal_system_id() const; + void _internal_set_system_id(::uint32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.core.SystemComponents) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 0, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::RepeatedField<::uint32_t> component_ids_; + mutable ::google::protobuf::internal::CachedSize _component_ids_cached_byte_size_; + ::uint32_t system_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_core_2fcore_2eproto; +};// ------------------------------------------------------------------- + class SubscribeConnectionStateRequest final : public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.core.SubscribeConnectionStateRequest) */ { public: @@ -538,6 +743,142 @@ class SetMavlinkTimeoutRequest final : friend struct ::TableStruct_core_2fcore_2eproto; };// ------------------------------------------------------------------- +class ListComponentsRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.core.ListComponentsRequest) */ { + public: + inline ListComponentsRequest() : ListComponentsRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR ListComponentsRequest(::google::protobuf::internal::ConstantInitialized); + + inline ListComponentsRequest(const ListComponentsRequest& from) + : ListComponentsRequest(nullptr, from) {} + ListComponentsRequest(ListComponentsRequest&& from) noexcept + : ListComponentsRequest() { + *this = ::std::move(from); + } + + inline ListComponentsRequest& operator=(const ListComponentsRequest& from) { + CopyFrom(from); + return *this; + } + inline ListComponentsRequest& operator=(ListComponentsRequest&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const ListComponentsRequest& default_instance() { + return *internal_default_instance(); + } + static inline const ListComponentsRequest* internal_default_instance() { + return reinterpret_cast( + &_ListComponentsRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + friend void swap(ListComponentsRequest& a, ListComponentsRequest& b) { + a.Swap(&b); + } + inline void Swap(ListComponentsRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ListComponentsRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ListComponentsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const ListComponentsRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const ListComponentsRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.core.ListComponentsRequest"; + } + protected: + explicit ListComponentsRequest(::google::protobuf::Arena* arena); + ListComponentsRequest(::google::protobuf::Arena* arena, const ListComponentsRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.core.ListComponentsRequest) + private: + class _Internal; + + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + PROTOBUF_TSAN_DECLARE_MEMBER + }; + friend struct ::TableStruct_core_2fcore_2eproto; +};// ------------------------------------------------------------------- + class ConnectionState final : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.core.ConnectionState) */ { public: @@ -713,6 +1054,189 @@ class ConnectionState final : friend struct ::TableStruct_core_2fcore_2eproto; };// ------------------------------------------------------------------- +class ListComponentsResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.core.ListComponentsResponse) */ { + public: + inline ListComponentsResponse() : ListComponentsResponse(nullptr) {} + ~ListComponentsResponse() override; + template + explicit PROTOBUF_CONSTEXPR ListComponentsResponse(::google::protobuf::internal::ConstantInitialized); + + inline ListComponentsResponse(const ListComponentsResponse& from) + : ListComponentsResponse(nullptr, from) {} + ListComponentsResponse(ListComponentsResponse&& from) noexcept + : ListComponentsResponse() { + *this = ::std::move(from); + } + + inline ListComponentsResponse& operator=(const ListComponentsResponse& from) { + CopyFrom(from); + return *this; + } + inline ListComponentsResponse& operator=(ListComponentsResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const ListComponentsResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ListComponentsResponse* internal_default_instance() { + return reinterpret_cast( + &_ListComponentsResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 7; + + friend void swap(ListComponentsResponse& a, ListComponentsResponse& b) { + a.Swap(&b); + } + inline void Swap(ListComponentsResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ListComponentsResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ListComponentsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ListComponentsResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ListComponentsResponse& from) { + ListComponentsResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(ListComponentsResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.core.ListComponentsResponse"; + } + protected: + explicit ListComponentsResponse(::google::protobuf::Arena* arena); + ListComponentsResponse(::google::protobuf::Arena* arena, const ListComponentsResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kSystemsFieldNumber = 1, + }; + // repeated .mavsdk.rpc.core.SystemComponents systems = 1; + int systems_size() const; + private: + int _internal_systems_size() const; + + public: + void clear_systems() ; + ::mavsdk::rpc::core::SystemComponents* mutable_systems(int index); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::core::SystemComponents >* + mutable_systems(); + private: + const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::core::SystemComponents>& _internal_systems() const; + ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::core::SystemComponents>* _internal_mutable_systems(); + public: + const ::mavsdk::rpc::core::SystemComponents& systems(int index) const; + ::mavsdk::rpc::core::SystemComponents* add_systems(); + const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::core::SystemComponents >& + systems() const; + // @@protoc_insertion_point(class_scope:mavsdk.rpc.core.ListComponentsResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::core::SystemComponents > systems_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_core_2fcore_2eproto; +};// ------------------------------------------------------------------- + class ConnectionStateResponse final : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.core.ConnectionStateResponse) */ { public: @@ -1068,6 +1592,135 @@ inline void ConnectionState::_internal_set_is_connected(bool value) { _impl_.is_connected_ = value; } +// ------------------------------------------------------------------- + +// ListComponentsRequest + +// ------------------------------------------------------------------- + +// SystemComponents + +// uint32 system_id = 1; +inline void SystemComponents::clear_system_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.system_id_ = 0u; +} +inline ::uint32_t SystemComponents::system_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.core.SystemComponents.system_id) + return _internal_system_id(); +} +inline void SystemComponents::set_system_id(::uint32_t value) { + _internal_set_system_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.core.SystemComponents.system_id) +} +inline ::uint32_t SystemComponents::_internal_system_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.system_id_; +} +inline void SystemComponents::_internal_set_system_id(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.system_id_ = value; +} + +// repeated uint32 component_ids = 2; +inline int SystemComponents::_internal_component_ids_size() const { + return _internal_component_ids().size(); +} +inline int SystemComponents::component_ids_size() const { + return _internal_component_ids_size(); +} +inline void SystemComponents::clear_component_ids() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.component_ids_.Clear(); +} +inline ::uint32_t SystemComponents::component_ids(int index) const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.core.SystemComponents.component_ids) + return _internal_component_ids().Get(index); +} +inline void SystemComponents::set_component_ids(int index, ::uint32_t value) { + _internal_mutable_component_ids()->Set(index, value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.core.SystemComponents.component_ids) +} +inline void SystemComponents::add_component_ids(::uint32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _internal_mutable_component_ids()->Add(value); + // @@protoc_insertion_point(field_add:mavsdk.rpc.core.SystemComponents.component_ids) +} +inline const ::google::protobuf::RepeatedField<::uint32_t>& SystemComponents::component_ids() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.core.SystemComponents.component_ids) + return _internal_component_ids(); +} +inline ::google::protobuf::RepeatedField<::uint32_t>* SystemComponents::mutable_component_ids() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.core.SystemComponents.component_ids) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_component_ids(); +} +inline const ::google::protobuf::RepeatedField<::uint32_t>& SystemComponents::_internal_component_ids() + const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.component_ids_; +} +inline ::google::protobuf::RepeatedField<::uint32_t>* SystemComponents::_internal_mutable_component_ids() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.component_ids_; +} + +// ------------------------------------------------------------------- + +// ListComponentsResponse + +// repeated .mavsdk.rpc.core.SystemComponents systems = 1; +inline int ListComponentsResponse::_internal_systems_size() const { + return _internal_systems().size(); +} +inline int ListComponentsResponse::systems_size() const { + return _internal_systems_size(); +} +inline void ListComponentsResponse::clear_systems() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.systems_.Clear(); +} +inline ::mavsdk::rpc::core::SystemComponents* ListComponentsResponse::mutable_systems(int index) + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.core.ListComponentsResponse.systems) + return _internal_mutable_systems()->Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::core::SystemComponents>* ListComponentsResponse::mutable_systems() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.core.ListComponentsResponse.systems) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_systems(); +} +inline const ::mavsdk::rpc::core::SystemComponents& ListComponentsResponse::systems(int index) const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.core.ListComponentsResponse.systems) + return _internal_systems().Get(index); +} +inline ::mavsdk::rpc::core::SystemComponents* ListComponentsResponse::add_systems() ABSL_ATTRIBUTE_LIFETIME_BOUND { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::mavsdk::rpc::core::SystemComponents* _add = _internal_mutable_systems()->Add(); + // @@protoc_insertion_point(field_add:mavsdk.rpc.core.ListComponentsResponse.systems) + return _add; +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::core::SystemComponents>& ListComponentsResponse::systems() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.core.ListComponentsResponse.systems) + return _internal_systems(); +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::core::SystemComponents>& +ListComponentsResponse::_internal_systems() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.systems_; +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::core::SystemComponents>* +ListComponentsResponse::_internal_mutable_systems() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.systems_; +} + #ifdef __GNUC__ #pragma GCC diagnostic pop #endif // __GNUC__